Update actions to ubuntu-latest (#14114)
[betaflight.git] / src / main / rx / sumh.c
blobc1c91eadcb0f4cd3cca14cd9aa1718af77282a96
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * References:
23 * http://fpv-treff.de/viewtopic.php?f=18&t=1368&start=3020#p44535
24 * http://fpv-community.de/showthread.php?29033-MultiWii-mit-Graupner-SUMD-SUMH-und-USB-Joystick-auf-ProMicro
27 #include <stdbool.h>
28 #include <stdint.h>
29 #include <stdlib.h>
31 #include "platform.h"
33 #ifdef USE_SERIALRX_SUMH
35 #include "common/utils.h"
37 #include "drivers/time.h"
39 #include "io/serial.h"
41 #ifdef USE_TELEMETRY
42 #include "telemetry/telemetry.h"
43 #endif
45 #include "pg/rx.h"
47 #include "rx/rx.h"
48 #include "rx/sumh.h"
50 #define SUMH_BAUDRATE 115200
52 #define SUMH_MAX_CHANNEL_COUNT 8
53 #define SUMH_FRAME_SIZE 21
55 static bool sumhFrameDone = false;
57 static uint8_t sumhFrame[SUMH_FRAME_SIZE];
58 static uint32_t sumhChannels[SUMH_MAX_CHANNEL_COUNT];
60 static serialPort_t *sumhPort;
62 // Receive ISR callback
63 static void sumhDataReceive(uint16_t c, void *data)
65 UNUSED(data);
67 uint32_t sumhTime;
68 static uint32_t sumhTimeLast, sumhTimeInterval;
69 static uint8_t sumhFramePosition;
71 sumhTime = micros();
72 sumhTimeInterval = sumhTime - sumhTimeLast;
73 sumhTimeLast = sumhTime;
74 if (sumhTimeInterval > 5000) {
75 sumhFramePosition = 0;
78 sumhFrame[sumhFramePosition] = (uint8_t) c;
79 if (sumhFramePosition == SUMH_FRAME_SIZE - 1) {
80 // FIXME at this point the value of 'c' is unused and un tested, what should it be, is it important?
81 sumhFrameDone = true;
82 } else {
83 sumhFramePosition++;
87 static uint8_t sumhFrameStatus(rxRuntimeState_t *rxRuntimeState)
89 UNUSED(rxRuntimeState);
91 uint8_t channelIndex;
93 if (!sumhFrameDone) {
94 return RX_FRAME_PENDING;
97 sumhFrameDone = false;
99 if (!((sumhFrame[0] == 0xA8) && (sumhFrame[SUMH_FRAME_SIZE - 2] == 0))) {
100 return RX_FRAME_PENDING;
103 for (channelIndex = 0; channelIndex < SUMH_MAX_CHANNEL_COUNT; channelIndex++) {
104 sumhChannels[channelIndex] = (((uint32_t)(sumhFrame[(channelIndex << 1) + 3]) << 8)
105 + sumhFrame[(channelIndex << 1) + 4]) / 6.4f - 375;
107 return RX_FRAME_COMPLETE;
110 static float sumhReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
112 UNUSED(rxRuntimeState);
114 if (chan >= SUMH_MAX_CHANNEL_COUNT) {
115 return 0;
118 return sumhChannels[chan];
121 bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
123 UNUSED(rxConfig);
125 rxRuntimeState->channelCount = SUMH_MAX_CHANNEL_COUNT;
126 rxRuntimeState->rcReadRawFn = sumhReadRawRC;
127 rxRuntimeState->rcFrameStatusFn = sumhFrameStatus;
129 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
130 if (!portConfig) {
131 return false;
134 #ifdef USE_TELEMETRY
135 bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
136 #else
137 bool portShared = false;
138 #endif
140 sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, NULL, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0));
142 #ifdef USE_TELEMETRY
143 if (portShared) {
144 telemetrySharedPort = sumhPort;
146 #endif
148 return sumhPort != NULL;
150 #endif