Adding missing commits
[inav.git] / src / main / rx / sbus.c
blob9b24361a091b34b12803eeb402499035b01d68f8
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_LOW,
58 STATE_SBUS26_PAYLOAD_HIGH,
59 STATE_SBUS_WAIT_SYNC
60 } sbusDecoderState_e;
62 typedef struct sbusFrameData_s {
63 sbusDecoderState_e state;
64 volatile sbusFrame_t frame;
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 (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) {
86 sbusFrameData->state = STATE_SBUS_SYNC;
89 switch (sbusFrameData->state) {
90 case STATE_SBUS_SYNC:
91 if (c == SBUS_FRAME_BEGIN_BYTE) {
92 sbusFrameData->position = 0;
93 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
94 sbusFrameData->state = STATE_SBUS_PAYLOAD;
95 } else if (c == SBUS26_FRAME0_BEGIN_BYTE) {
96 sbusFrameData->position = 0;
97 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
98 sbusFrameData->state = STATE_SBUS26_PAYLOAD_LOW;
99 } else if (c == SBUS26_FRAME1_BEGIN_BYTE) {
100 sbusFrameData->position = 0;
101 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
102 sbusFrameData->state = STATE_SBUS26_PAYLOAD_HIGH;
104 break;
106 case STATE_SBUS_PAYLOAD:
107 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
109 if (sbusFrameData->position == SBUS_FRAME_SIZE) {
110 const sbusFrame_t * frame = (sbusFrame_t *)&sbusFrameData->buffer[0];
111 bool frameValid = false;
113 // Do some sanity check
114 switch (frame->endByte) {
115 case 0x00: // This is S.BUS 1
116 case 0x04: // S.BUS 2 telemetry page 1
117 case 0x14: // S.BUS 2 telemetry page 2
118 case 0x24: // S.BUS 2 telemetry page 3
119 case 0x34: // S.BUS 2 telemetry page 4
120 if(frame->endByte & 0x4) {
121 sbus2ActiveTelemetryPage = (frame->endByte >> 4) & 0xF;
122 frameTime = currentTimeUs;
123 } else {
124 sbus2ActiveTelemetryPage = 0;
125 sbus2ActiveTelemetrySlot = 0;
126 frameTime = -1;
130 frameValid = true;
131 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
132 break;
134 default: // Failed end marker
135 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
136 break;
139 // Frame seems sane, pass data to decoder
140 if (!sbusFrameData->frameDone && frameValid) {
142 memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE);
143 sbusFrameData->frameDone = true;
144 sbusFrameData->is26channels = false;
147 break;
149 case STATE_SBUS26_PAYLOAD_LOW:
150 case STATE_SBUS26_PAYLOAD_HIGH:
151 sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c;
153 if (sbusFrameData->position == SBUS_FRAME_SIZE) {
154 const sbusFrame_t * frame = (sbusFrame_t *)&sbusFrameData->buffer[0];
155 bool frameValid = false;
157 // Do some sanity check
158 switch (frame->endByte) {
159 case 0x20: // S.BUS 2 telemetry page 1
160 case 0x24: // S.BUS 2 telemetry page 2
161 case 0x28: // S.BUS 2 telemetry page 3
162 case 0x2C: // S.BUS 2 telemetry page 4
163 if (frame->syncByte == SBUS26_FRAME1_BEGIN_BYTE) {
164 sbus2ActiveTelemetryPage = (frame->endByte >> 2) & 0x3;
165 frameTime = currentTimeUs;
168 frameValid = true;
169 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
170 break;
172 default: // Failed end marker
173 sbusFrameData->state = STATE_SBUS_WAIT_SYNC;
174 break;
177 // Frame seems sane, pass data to decoder
178 if (!sbusFrameData->frameDone && frameValid) {
179 memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE);
180 sbusFrameData->frameDone = true;
181 sbusFrameData->is26channels = true;
184 break;
188 case STATE_SBUS_WAIT_SYNC:
189 // Stay at this state and do nothing. Exit will be handled before byte is processed if the
190 // inter-frame gap is long enough
191 break;
195 static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
197 sbusFrameData_t *sbusFrameData = rxRuntimeConfig->frameData;
199 if (!sbusFrameData->frameDone) {
200 return RX_FRAME_PENDING;
203 // Decode channel data and store return value
204 const uint8_t retValue = sbusFrameData->is26channels ?
205 sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels, (sbusFrameData->frame.syncByte == SBUS26_FRAME1_BEGIN_BYTE)) :
206 sbusChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels);
208 // Reset the frameDone flag - tell ISR that we're ready to receive next frame
209 sbusFrameData->frameDone = false;
211 //taskSendSbus2Telemetry(micros());
213 // Calculate "virtual link quality based on packet loss metric"
214 if (retValue & RX_FRAME_COMPLETE) {
215 lqTrackerAccumulate(rxRuntimeConfig->lqTracker, ((retValue & RX_FRAME_DROPPED) || (retValue & RX_FRAME_FAILSAFE)) ? 0 : RSSI_MAX_VALUE);
218 return retValue;
221 static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint32_t sbusBaudRate)
223 static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
224 static sbusFrameData_t sbusFrameData;
226 rxRuntimeConfig->channelData = sbusChannelData;
227 rxRuntimeConfig->frameData = &sbusFrameData;
229 sbusChannelsInit(rxRuntimeConfig);
231 rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
233 rxRuntimeConfig->rcFrameStatusFn = sbusFrameStatus;
235 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
236 if (!portConfig) {
237 return false;
240 #ifdef USE_TELEMETRY
241 bool portShared = telemetryCheckRxPortShared(portConfig);
242 #else
243 bool portShared = false;
244 #endif
246 serialPort_t *sBusPort = openSerialPort(portConfig->identifier,
247 FUNCTION_RX_SERIAL,
248 sbusDataReceive,
249 &sbusFrameData,
250 sbusBaudRate,
251 (portShared || rxConfig->serialrx_provider == SERIALRX_SBUS2) ? MODE_RXTX : MODE_RX,
252 SBUS_PORT_OPTIONS |
253 (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) |
254 ((rxConfig->serialrx_provider == SERIALRX_SBUS2) ? SERIAL_BIDIR : 0) |
255 (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0)
258 #ifdef USE_TELEMETRY
259 if (portShared || (rxConfig->serialrx_provider == SERIALRX_SBUS2)) {
260 telemetrySharedPort = sBusPort;
262 #endif
264 return sBusPort != NULL;
267 bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
269 return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE);
272 bool sbusInitFast(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
274 return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE_FAST);
277 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2)
278 timeUs_t sbusGetLastFrameTime(void) {
279 return frameTime;
282 uint8_t sbusGetCurrentTelemetryNextSlot(void)
284 uint8_t current = sbus2ActiveTelemetrySlot;
285 sbus2ActiveTelemetrySlot++;
286 return current;
289 uint8_t sbusGetCurrentTelemetryPage(void) {
290 return sbus2ActiveTelemetryPage;
292 #endif // USE_TELEMETRY && USE_SBUS2_TELEMETRY
294 #endif // USE_SERIAL_RX