MAMBAF405_2022A target
[inav.git] / src / main / rx / sumh.c
blob33ffa0e07d3be3f39857f1069903ff22cb88c4f4
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
19 * References:
20 * http://fpv-treff.de/viewtopic.php?f=18&t=1368&start=3020#p44535
21 * http://fpv-community.de/showthread.php?29033-MultiWii-mit-Graupner-SUMD-SUMH-und-USB-Joystick-auf-ProMicro
24 #include <stdbool.h>
25 #include <stdint.h>
26 #include <stdlib.h>
28 #include "platform.h"
30 #ifdef USE_SERIALRX_SUMH
32 #include "common/utils.h"
34 #include "drivers/serial.h"
35 #include "drivers/time.h"
37 #include "io/serial.h"
39 #include "rx/rx.h"
40 #include "rx/sumh.h"
42 #include "telemetry/telemetry.h"
44 // driver for SUMH receiver using UART2
46 #define SUMH_BAUDRATE 115200
48 #define SUMH_MAX_CHANNEL_COUNT 8
49 #define SUMH_FRAME_SIZE 21
51 static bool sumhFrameDone = false;
53 static uint8_t sumhFrame[SUMH_FRAME_SIZE];
54 static uint32_t sumhChannels[SUMH_MAX_CHANNEL_COUNT];
56 static serialPort_t *sumhPort;
59 // Receive ISR callback
60 static void sumhDataReceive(uint16_t c, void *rxCallbackData)
62 UNUSED(rxCallbackData);
64 timeUs_t sumhTime;
65 timeDelta_t sumhTimeInterval;
66 static timeUs_t sumhTimeLast;
67 static uint8_t sumhFramePosition;
69 sumhTime = micros();
70 sumhTimeInterval = cmpTimeUs(sumhTime, sumhTimeLast);
71 sumhTimeLast = sumhTime;
72 if (sumhTimeInterval > MS2US(5)) {
73 sumhFramePosition = 0;
76 sumhFrame[sumhFramePosition] = (uint8_t) c;
77 if (sumhFramePosition == SUMH_FRAME_SIZE - 1) {
78 // FIXME at this point the value of 'c' is unused and un tested, what should it be, is it important?
79 sumhFrameDone = true;
80 } else {
81 sumhFramePosition++;
85 uint8_t sumhFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
87 UNUSED(rxRuntimeConfig);
89 uint8_t channelIndex;
91 if (!sumhFrameDone) {
92 return RX_FRAME_PENDING;
95 sumhFrameDone = false;
97 if (!((sumhFrame[0] == 0xA8) && (sumhFrame[SUMH_FRAME_SIZE - 2] == 0))) {
98 return RX_FRAME_PENDING;
101 for (channelIndex = 0; channelIndex < SUMH_MAX_CHANNEL_COUNT; channelIndex++) {
102 sumhChannels[channelIndex] = (((uint32_t)(sumhFrame[(channelIndex << 1) + 3]) << 8)
103 + sumhFrame[(channelIndex << 1) + 4]) / 6.4f - 375;
105 return RX_FRAME_COMPLETE;
108 static uint16_t sumhReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
110 UNUSED(rxRuntimeConfig);
112 if (chan >= SUMH_MAX_CHANNEL_COUNT) {
113 return 0;
116 return sumhChannels[chan];
119 bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
121 UNUSED(rxConfig);
123 rxRuntimeConfig->channelCount = SUMH_MAX_CHANNEL_COUNT;
124 rxRuntimeConfig->rxRefreshRate = 11000;
126 rxRuntimeConfig->rcReadRawFn = sumhReadRawRC;
127 rxRuntimeConfig->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);
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, SERIAL_NOT_INVERTED);
142 #ifdef USE_TELEMETRY
143 if (portShared) {
144 telemetrySharedPort = sumhPort;
146 #endif
148 return sumhPort != NULL;
150 #endif // USE_SERIALRX_SUMH