remove test code
[inav.git] / src / main / rx / sumd.c
blob7097b6c9fd2363e9d981972695ddc738463f8bdc
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/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
22 #include "platform.h"
24 #ifdef USE_SERIALRX_SUMD
26 #include "common/utils.h"
28 #include "drivers/time.h"
29 #include "drivers/serial.h"
30 #include "drivers/serial_uart.h"
32 #include "io/serial.h"
34 #include "rx/rx.h"
35 #include "rx/sumd.h"
37 #include "telemetry/telemetry.h"
39 // driver for SUMD receiver using UART2
41 // FIXME test support for more than 8 channels, should probably work up to 12 channels
43 #define SUMD_SYNCBYTE 0xA8
44 #define SUMD_MAX_CHANNEL 16
45 #define SUMD_BUFFSIZE (SUMD_MAX_CHANNEL * 2 + 5) // 6 channels + 5 = 17 bytes for 6 channels
47 #define SUMD_BAUDRATE 115200
49 static bool sumdFrameDone = false;
50 static uint16_t sumdChannels[SUMD_MAX_CHANNEL];
51 static uint16_t crc;
53 #define CRC_POLYNOME 0x1021
55 // CRC calculation, adds a 8 bit unsigned to 16 bit crc
56 static void CRC16(uint8_t value)
58 uint8_t i;
60 crc = crc ^ (int16_t)value << 8;
61 for (i = 0; i < 8; i++) {
62 if (crc & 0x8000)
63 crc = (crc << 1) ^ CRC_POLYNOME;
64 else
65 crc = (crc << 1);
69 static uint8_t sumd[SUMD_BUFFSIZE] = { 0, };
70 static uint8_t sumdChannelCount;
72 // Receive ISR callback
73 static void sumdDataReceive(uint16_t c, void *rxCallbackData)
75 UNUSED(rxCallbackData);
77 timeUs_t sumdTime;
78 static timeUs_t sumdTimeLast;
79 static uint8_t sumdIndex;
81 sumdTime = micros();
82 if (cmpTimeUs(sumdTime, sumdTimeLast) > MS2US(4))
83 sumdIndex = 0;
84 sumdTimeLast = sumdTime;
86 if (sumdIndex == 0) {
87 if (c != SUMD_SYNCBYTE)
88 return;
89 else
91 sumdFrameDone = false; // lazy main loop didnt fetch the stuff
92 crc = 0;
95 if (sumdIndex == 2)
96 sumdChannelCount = (uint8_t)c;
97 if (sumdIndex < SUMD_BUFFSIZE)
98 sumd[sumdIndex] = (uint8_t)c;
99 sumdIndex++;
100 if (sumdIndex < sumdChannelCount * 2 + 4)
101 CRC16((uint8_t)c);
102 else
103 if (sumdIndex == sumdChannelCount * 2 + 5) {
104 sumdIndex = 0;
105 sumdFrameDone = true;
109 #define SUMD_OFFSET_CHANNEL_1_HIGH 3
110 #define SUMD_OFFSET_CHANNEL_1_LOW 4
111 #define SUMD_BYTES_PER_CHANNEL 2
114 #define SUMD_FRAME_STATE_OK 0x01
115 #define SUMD_FRAME_STATE_FAILSAFE 0x81
117 static uint8_t sumdFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
119 UNUSED(rxRuntimeConfig);
121 uint8_t channelIndex;
123 uint8_t frameStatus = RX_FRAME_PENDING;
125 if (!sumdFrameDone) {
126 return frameStatus;
129 sumdFrameDone = false;
131 // verify CRC
132 if (crc != ((sumd[SUMD_BYTES_PER_CHANNEL * sumdChannelCount + SUMD_OFFSET_CHANNEL_1_HIGH] << 8) |
133 (sumd[SUMD_BYTES_PER_CHANNEL * sumdChannelCount + SUMD_OFFSET_CHANNEL_1_LOW])))
134 return frameStatus;
136 switch (sumd[1]) {
137 case SUMD_FRAME_STATE_FAILSAFE:
138 frameStatus = RX_FRAME_COMPLETE | RX_FRAME_FAILSAFE;
139 break;
140 case SUMD_FRAME_STATE_OK:
141 frameStatus = RX_FRAME_COMPLETE;
142 break;
143 default:
144 return frameStatus;
147 if (sumdChannelCount > SUMD_MAX_CHANNEL)
148 sumdChannelCount = SUMD_MAX_CHANNEL;
150 for (channelIndex = 0; channelIndex < sumdChannelCount; channelIndex++) {
151 sumdChannels[channelIndex] = (
152 (sumd[SUMD_BYTES_PER_CHANNEL * channelIndex + SUMD_OFFSET_CHANNEL_1_HIGH] << 8) |
153 sumd[SUMD_BYTES_PER_CHANNEL * channelIndex + SUMD_OFFSET_CHANNEL_1_LOW]
156 return frameStatus;
159 static uint16_t sumdReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
161 UNUSED(rxRuntimeConfig);
162 return sumdChannels[chan] / 8;
165 bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
167 UNUSED(rxConfig);
169 rxRuntimeConfig->channelCount = SUMD_MAX_CHANNEL;
170 rxRuntimeConfig->rcReadRawFn = sumdReadRawRC;
171 rxRuntimeConfig->rcFrameStatusFn = sumdFrameStatus;
173 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
174 if (!portConfig) {
175 return false;
178 #ifdef USE_TELEMETRY
179 bool portShared = telemetryCheckRxPortShared(portConfig);
180 #else
181 bool portShared = false;
182 #endif
184 serialPort_t *sumdPort = openSerialPort(portConfig->identifier,
185 FUNCTION_RX_SERIAL,
186 sumdDataReceive,
187 NULL,
188 SUMD_BAUDRATE,
189 portShared ? MODE_RXTX : MODE_RX,
190 SERIAL_NOT_INVERTED | (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0)
193 #ifdef USE_TELEMETRY
194 if (portShared) {
195 telemetrySharedPort = sumdPort;
197 #endif
199 return sumdPort != NULL;
201 #endif // USE_SERIALRX_SUMD