Merge pull request #10492 from iNavFlight/MrD_Update-OSD.md-for-8.0
[inav.git] / src / main / rx / sbus.c
blobf08267eeb1d1863693aa225456c6521c87186b63
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 static uint8_t sbus2ShortFrameInterval = 0;
75 timeUs_t frameTime = 0;
77 // Receive ISR callback
78 static void sbusDataReceive(uint16_t c, void *data)
80 sbusFrameData_t *sbusFrameData = data;
81 const timeUs_t currentTimeUs = micros();
82 const timeDelta_t timeSinceLastByteUs = cmpTimeUs(currentTimeUs, sbusFrameData->lastActivityTimeUs);
83 sbusFrameData->lastActivityTimeUs = currentTimeUs;
85 const int32_t syncInterval = sbus2ShortFrameInterval
86 ? ((6300 - SBUS_BYTE_TIME_US(25)) / 2)
87 : rxConfig()->sbusSyncInterval;
90 // 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
91 if ((sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= syncInterval)
92 || (rxConfig()->serialrx_provider == SERIALRX_SBUS2 && timeSinceLastByteUs >= SBUS_BYTE_TIME_US(3))) {
93 sbusFrameData->state = STATE_SBUS_SYNC;
94 } else if ((sbusFrameData->state == STATE_SBUS_PAYLOAD || sbusFrameData->state == STATE_SBUS26_PAYLOAD) && timeSinceLastByteUs >= SBUS_BYTE_TIME_US(3)) {
95 // payload is pausing too long, possible if some telemetry have been sent between frames, or false positves mid frame
96 sbusFrameData->state = STATE_SBUS_SYNC;
99 switch (sbusFrameData->state) {
100 case STATE_SBUS_SYNC:
101 if (c == SBUS_FRAME_BEGIN_BYTE) {
102 sbusFrameData->position = 0;
103 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
104 sbusFrameData->state = STATE_SBUS_PAYLOAD;
105 } else if (c == SBUS2_HIGHFRAME_BEGIN_BYTE) {
106 sbusFrameData->position = 0;
107 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
108 sbusFrameData->state = STATE_SBUS26_PAYLOAD;
110 break;
112 case STATE_SBUS_PAYLOAD:
113 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
115 if (sbusFrameData->position == SBUS_FRAME_SIZE) {
116 const sbusFrame_t * frame = (sbusFrame_t *)&sbusFrameData->buffer[0];
117 bool frameValid = false;
119 // Do some sanity check
120 switch (frame->endByte) {
121 case 0x00: // This is S.BUS 1
122 case 0x04: // S.BUS 2 telemetry page 1
123 case 0x08: // S.BUS 2 fast frame pace, not telemetry.
124 case 0x14: // S.BUS 2 telemetry page 2
125 case 0x24: // S.BUS 2 telemetry page 3
126 case 0x34: // S.BUS 2 telemetry page 4
127 if(frame->endByte & 0x4) {
128 sbus2ActiveTelemetryPage = (frame->endByte >> 4) & 0xF;
129 frameTime = currentTimeUs;
130 } else if(frame->endByte == 0x08) {
131 sbus2ShortFrameInterval = 1;
132 } else {
133 sbus2ActiveTelemetryPage = 0;
134 sbus2ActiveTelemetrySlot = 0;
135 frameTime = -1;
138 frameValid = true;
139 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
140 break;
142 default: // Failed end marker
143 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
144 break;
147 // Frame seems sane, pass data to decoder
148 if (!sbusFrameData->frameDone && frameValid) {
150 memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE);
151 sbusFrameData->frameDone = true;
154 break;
156 case STATE_SBUS26_PAYLOAD:
157 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
159 if (sbusFrameData->position == SBUS_FRAME_SIZE) {
160 const sbusFrame_t * frame = (sbusFrame_t *)&sbusFrameData->buffer[0];
161 bool frameValid = false;
163 // Do some sanity check
164 switch (frame->endByte) {
165 case 0x00:
166 case 0x04: // S.BUS 2 telemetry page 1
167 case 0x14: // S.BUS 2 telemetry page 2
168 case 0x24: // S.BUS 2 telemetry page 3
169 case 0x34: // S.BUS 2 telemetry page 4
170 frameTime = -1; // ignore this one, as you can't fit telemetry between this and the next frame.
171 frameValid = true;
172 sbusFrameData->state = STATE_SBUS_SYNC; // Next piece of data should be a sync byte
173 break;
175 default: // Failed end marker
176 frameValid = false;
177 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
178 break;
181 // Frame seems sane, pass data to decoder
182 if (!sbusFrameData->frameDone && frameValid) {
183 memcpy((void *)&sbusFrameData->frameHigh, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE);
184 sbusFrameData->frameDone = true;
185 sbusFrameData->is26channels = true;
188 break;
190 case STATE_SBUS_WAIT_SYNC:
191 // Stay at this state and do nothing. Exit will be handled before byte is processed if the
192 // inter-frame gap is long enough
193 break;
197 static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
199 sbusFrameData_t *sbusFrameData = rxRuntimeConfig->frameData;
201 if (!sbusFrameData->frameDone) {
202 return RX_FRAME_PENDING;
205 uint8_t retValue = 0;
206 // Decode channel data and store return value
207 if (sbusFrameData->is26channels)
209 retValue = sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels, false);
210 retValue |= sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frameHigh.channels, true);
212 } else {
213 retValue = sbusChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels);
216 // Reset the frameDone flag - tell ISR that we're ready to receive next frame
217 sbusFrameData->frameDone = false;
219 // Calculate "virtual link quality based on packet loss metric"
220 if (retValue & RX_FRAME_COMPLETE) {
221 lqTrackerAccumulate(rxRuntimeConfig->lqTracker, ((retValue & RX_FRAME_DROPPED) || (retValue & RX_FRAME_FAILSAFE)) ? 0 : RSSI_MAX_VALUE);
224 return retValue;
227 static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint32_t sbusBaudRate)
229 static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
230 static sbusFrameData_t sbusFrameData = { .is26channels = false};
232 rxRuntimeConfig->channelData = sbusChannelData;
233 rxRuntimeConfig->frameData = &sbusFrameData;
235 sbusChannelsInit(rxRuntimeConfig);
237 rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
239 rxRuntimeConfig->rcFrameStatusFn = sbusFrameStatus;
241 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
242 if (!portConfig) {
243 return false;
246 #ifdef USE_TELEMETRY
247 bool portShared = telemetryCheckRxPortShared(portConfig);
248 #else
249 bool portShared = false;
250 #endif
252 serialPort_t *sBusPort = openSerialPort(portConfig->identifier,
253 FUNCTION_RX_SERIAL,
254 sbusDataReceive,
255 &sbusFrameData,
256 sbusBaudRate,
257 (portShared || rxConfig->serialrx_provider == SERIALRX_SBUS2) ? MODE_RXTX : MODE_RX,
258 SBUS_PORT_OPTIONS |
259 (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) |
260 ((rxConfig->serialrx_provider == SERIALRX_SBUS2) ? SERIAL_BIDIR : 0) |
261 (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0)
264 #ifdef USE_TELEMETRY
265 if (portShared || (rxConfig->serialrx_provider == SERIALRX_SBUS2)) {
266 telemetrySharedPort = sBusPort;
268 #endif
270 return sBusPort != NULL;
273 bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
275 return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE);
278 bool sbusInitFast(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
280 return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE_FAST);
283 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2)
284 timeUs_t sbusGetLastFrameTime(void) {
285 return frameTime;
288 uint8_t sbusGetCurrentTelemetryNextSlot(void)
290 uint8_t current = sbus2ActiveTelemetrySlot;
291 sbus2ActiveTelemetrySlot++;
292 return current;
295 uint8_t sbusGetCurrentTelemetryPage(void) {
296 return sbus2ActiveTelemetryPage;
298 #endif // USE_TELEMETRY && USE_SBUS2_TELEMETRY
300 #endif // USE_SERIAL_RX