Cleanup and blackbox changes
[inav.git] / src / main / rx / sbus.c
blob1549ba74a8bb71be5c9c52b11838f08ba5ac22b8
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>
21 #include <string.h>
23 #include "platform.h"
25 #ifdef USE_SERIAL_RX
27 #include "build/debug.h"
29 #include "common/utils.h"
31 #include "drivers/time.h"
33 #include "io/serial.h"
35 #ifdef USE_TELEMETRY
36 #include "telemetry/telemetry.h"
37 #endif
39 #include "rx/rx.h"
40 #include "rx/sbus.h"
41 #include "rx/sbus_channels.h"
44 * Observations
46 * FrSky X8R
47 * time between frames: 6ms.
48 * time to send frame: 3ms.
50 * Futaba R6208SB/R6303SB
51 * time between frames: 11ms.
52 * time to send frame: 3ms.
54 typedef enum {
55 STATE_SBUS_SYNC = 0,
56 STATE_SBUS_PAYLOAD,
57 STATE_SBUS26_PAYLOAD,
58 STATE_SBUS_WAIT_SYNC
59 } sbusDecoderState_e;
61 typedef struct sbusFrameData_s {
62 sbusDecoderState_e state;
63 volatile sbusFrame_t frame;
64 volatile sbusFrame_t frameHigh;
65 volatile bool frameDone;
66 volatile bool is26channels;
67 uint8_t buffer[SBUS_FRAME_SIZE];
68 uint8_t position;
69 timeUs_t lastActivityTimeUs;
70 } sbusFrameData_t;
72 static uint8_t sbus2ActiveTelemetryPage = 0;
73 static uint8_t sbus2ActiveTelemetrySlot = 0;
74 timeUs_t frameTime = 0;
76 // Receive ISR callback
77 static void sbusDataReceive(uint16_t c, void *data)
79 sbusFrameData_t *sbusFrameData = data;
80 const timeUs_t currentTimeUs = micros();
81 const timeDelta_t timeSinceLastByteUs = cmpTimeUs(currentTimeUs, sbusFrameData->lastActivityTimeUs);
82 sbusFrameData->lastActivityTimeUs = currentTimeUs;
84 // Handle inter-frame gap. We dwell in STATE_SBUS_WAIT_SYNC state ignoring all incoming bytes until we get long enough quite period on the wire
85 if (timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) {
86 sbusFrameData->state = STATE_SBUS_SYNC;
87 } else if ((sbusFrameData->state == STATE_SBUS_PAYLOAD || sbusFrameData->state == STATE_SBUS26_PAYLOAD) && timeSinceLastByteUs >= 300) {
88 // payload is pausing too long, possible if some telemetry have been sent between frames
89 sbusFrameData->state = STATE_SBUS_SYNC;
92 switch (sbusFrameData->state) {
93 case STATE_SBUS_SYNC:
94 if (c == SBUS_FRAME_BEGIN_BYTE) {
95 sbusFrameData->position = 0;
96 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
97 sbusFrameData->state = STATE_SBUS_PAYLOAD;
98 } else if ((uint8_t)c == SBUS26_FRAME_BEGIN_BYTE) {
99 sbusFrameData->position = 0;
100 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
101 sbusFrameData->state = STATE_SBUS26_PAYLOAD;
103 break;
105 case STATE_SBUS_PAYLOAD:
106 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
108 if (sbusFrameData->position == SBUS_FRAME_SIZE) {
109 const sbusFrame_t * frame = (sbusFrame_t *)&sbusFrameData->buffer[0];
110 bool frameValid = false;
112 // Do some sanity check
113 switch (frame->endByte) {
114 case 0x00: // This is S.BUS 1
115 case 0x04: // S.BUS 2 telemetry page 1
116 case 0x14: // S.BUS 2 telemetry page 2
117 case 0x24: // S.BUS 2 telemetry page 3
118 case 0x34: // S.BUS 2 telemetry page 4
119 if(frame->endByte & 0x4) {
120 sbus2ActiveTelemetryPage = (frame->endByte >> 4) & 0xF;
121 frameTime = currentTimeUs;
122 } else {
123 sbus2ActiveTelemetryPage = 0;
124 sbus2ActiveTelemetrySlot = 0;
125 frameTime = -1;
128 frameValid = true;
129 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
130 break;
132 default: // Failed end marker
133 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
134 break;
137 // Frame seems sane, pass data to decoder
138 if (!sbusFrameData->frameDone && frameValid) {
140 memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE);
141 sbusFrameData->frameDone = true;
144 break;
146 case STATE_SBUS26_PAYLOAD:
147 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
149 if (sbusFrameData->position == SBUS_FRAME_SIZE) {
150 const sbusFrame_t * frame = (sbusFrame_t *)&sbusFrameData->buffer[0];
151 bool frameValid = false;
153 // Do some sanity check
154 switch (frame->endByte) {
155 case 0x00:
156 case 0x04: // S.BUS 2 telemetry page 1
157 case 0x14: // S.BUS 2 telemetry page 2
158 case 0x24: // S.BUS 2 telemetry page 3
159 case 0x34: // S.BUS 2 telemetry page 4
160 frameTime = -1; // ignore this one, as you can't fit telemetry between this and the next frame.
161 frameValid = true;
162 sbusFrameData->state = STATE_SBUS_SYNC; // Next piece of data should be a sync byte
163 break;
165 default: // Failed end marker
166 frameValid = false;
167 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
168 break;
171 // Frame seems sane, pass data to decoder
172 if (!sbusFrameData->frameDone && frameValid) {
173 memcpy((void *)&sbusFrameData->frameHigh, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE);
174 sbusFrameData->frameDone = true;
175 sbusFrameData->is26channels = true;
178 break;
180 case STATE_SBUS_WAIT_SYNC:
181 // Stay at this state and do nothing. Exit will be handled before byte is processed if the
182 // inter-frame gap is long enough
183 if (c == SBUS26_FRAME_BEGIN_BYTE || c == 0xF2 || c == 0x2c) {
184 sbusFrameData->position = 0;
185 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
186 sbusFrameData->state = STATE_SBUS26_PAYLOAD;
189 break;
193 static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
195 sbusFrameData_t *sbusFrameData = rxRuntimeConfig->frameData;
197 if (!sbusFrameData->frameDone) {
198 return RX_FRAME_PENDING;
201 uint8_t retValue = 0;
202 // Decode channel data and store return value
203 if (sbusFrameData->is26channels)
205 retValue = sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels, false);
206 retValue |= sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frameHigh.channels, true);
208 } else {
209 retValue = sbusChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels);
212 // Reset the frameDone flag - tell ISR that we're ready to receive next frame
213 sbusFrameData->frameDone = false;
215 // Calculate "virtual link quality based on packet loss metric"
216 if (retValue & RX_FRAME_COMPLETE) {
217 lqTrackerAccumulate(rxRuntimeConfig->lqTracker, ((retValue & RX_FRAME_DROPPED) || (retValue & RX_FRAME_FAILSAFE)) ? 0 : RSSI_MAX_VALUE);
220 return retValue;
223 static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint32_t sbusBaudRate)
225 static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
226 static sbusFrameData_t sbusFrameData = { .is26channels = false};
228 rxRuntimeConfig->channelData = sbusChannelData;
229 rxRuntimeConfig->frameData = &sbusFrameData;
231 sbusChannelsInit(rxRuntimeConfig);
233 rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
235 rxRuntimeConfig->rcFrameStatusFn = sbusFrameStatus;
237 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
238 if (!portConfig) {
239 return false;
242 #ifdef USE_TELEMETRY
243 bool portShared = telemetryCheckRxPortShared(portConfig);
244 #else
245 bool portShared = false;
246 #endif
248 serialPort_t *sBusPort = openSerialPort(portConfig->identifier,
249 FUNCTION_RX_SERIAL,
250 sbusDataReceive,
251 &sbusFrameData,
252 sbusBaudRate,
253 (portShared || rxConfig->serialrx_provider == SERIALRX_SBUS2) ? MODE_RXTX : MODE_RX,
254 SBUS_PORT_OPTIONS |
255 (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) |
256 ((rxConfig->serialrx_provider == SERIALRX_SBUS2) ? SERIAL_BIDIR : 0) |
257 (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0)
260 #ifdef USE_TELEMETRY
261 if (portShared || (rxConfig->serialrx_provider == SERIALRX_SBUS2)) {
262 telemetrySharedPort = sBusPort;
264 #endif
266 return sBusPort != NULL;
269 bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
271 return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE);
274 bool sbusInitFast(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
276 return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE_FAST);
279 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2)
280 timeUs_t sbusGetLastFrameTime(void) {
281 return frameTime;
284 uint8_t sbusGetCurrentTelemetryNextSlot(void)
286 uint8_t current = sbus2ActiveTelemetrySlot;
287 sbus2ActiveTelemetrySlot++;
288 return current;
291 uint8_t sbusGetCurrentTelemetryPage(void) {
292 return sbus2ActiveTelemetryPage;
294 #endif // USE_TELEMETRY && USE_SBUS2_TELEMETRY
296 #endif // USE_SERIAL_RX