Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / rx / sumh.c
blob9dc7d8289661b51d1413fec726bc24ac9079bfdc
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;
63 // Receive ISR callback
64 static void sumhDataReceive(uint16_t c, void *data)
66 UNUSED(data);
68 uint32_t sumhTime;
69 static uint32_t sumhTimeLast, sumhTimeInterval;
70 static uint8_t sumhFramePosition;
72 sumhTime = micros();
73 sumhTimeInterval = sumhTime - sumhTimeLast;
74 sumhTimeLast = sumhTime;
75 if (sumhTimeInterval > 5000) {
76 sumhFramePosition = 0;
79 sumhFrame[sumhFramePosition] = (uint8_t) c;
80 if (sumhFramePosition == SUMH_FRAME_SIZE - 1) {
81 // FIXME at this point the value of 'c' is unused and un tested, what should it be, is it important?
82 sumhFrameDone = true;
83 } else {
84 sumhFramePosition++;
88 static uint8_t sumhFrameStatus(rxRuntimeState_t *rxRuntimeState)
90 UNUSED(rxRuntimeState);
92 uint8_t channelIndex;
94 if (!sumhFrameDone) {
95 return RX_FRAME_PENDING;
98 sumhFrameDone = false;
100 if (!((sumhFrame[0] == 0xA8) && (sumhFrame[SUMH_FRAME_SIZE - 2] == 0))) {
101 return RX_FRAME_PENDING;
104 for (channelIndex = 0; channelIndex < SUMH_MAX_CHANNEL_COUNT; channelIndex++) {
105 sumhChannels[channelIndex] = (((uint32_t)(sumhFrame[(channelIndex << 1) + 3]) << 8)
106 + sumhFrame[(channelIndex << 1) + 4]) / 6.4f - 375;
108 return RX_FRAME_COMPLETE;
111 static float sumhReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
113 UNUSED(rxRuntimeState);
115 if (chan >= SUMH_MAX_CHANNEL_COUNT) {
116 return 0;
119 return sumhChannels[chan];
122 bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
124 UNUSED(rxConfig);
126 rxRuntimeState->channelCount = SUMH_MAX_CHANNEL_COUNT;
127 rxRuntimeState->rxRefreshRate = 11000;
129 rxRuntimeState->rcReadRawFn = sumhReadRawRC;
130 rxRuntimeState->rcFrameStatusFn = sumhFrameStatus;
132 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
133 if (!portConfig) {
134 return false;
137 #ifdef USE_TELEMETRY
138 bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
139 #else
140 bool portShared = false;
141 #endif
143 sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, NULL, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0));
145 #ifdef USE_TELEMETRY
146 if (portShared) {
147 telemetrySharedPort = sumhPort;
149 #endif
151 return sumhPort != NULL;
153 #endif