Reset protocol level RX frame delta after reading
[betaflight.git] / src / main / rx / sbus.c
blob12660b8f22462b5bf188dd8cd3270c2a40a8e67f
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/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <stdlib.h>
25 #include "platform.h"
27 #ifdef USE_SERIALRX_SBUS
29 #include "build/debug.h"
31 #include "common/utils.h"
33 #include "drivers/time.h"
35 #include "io/serial.h"
37 #ifdef USE_TELEMETRY
38 #include "telemetry/telemetry.h"
39 #endif
41 #include "pg/rx.h"
43 #include "rx/rx.h"
44 #include "rx/sbus.h"
45 #include "rx/sbus_channels.h"
48 * Observations
50 * FrSky X8R
51 * time between frames: 6ms.
52 * time to send frame: 3ms.
54 * Futaba R6208SB/R6303SB
55 * time between frames: 11ms.
56 * time to send frame: 3ms.
59 #define SBUS_BAUDRATE 100000
60 #define SBUS_RX_REFRESH_RATE 11000
61 #define SBUS_TIME_NEEDED_PER_FRAME 3000
63 #define SBUS_FAST_BAUDRATE 200000
64 #define SBUS_FAST_RX_REFRESH_RATE 6000
66 #define SBUS_STATE_FAILSAFE (1 << 0)
67 #define SBUS_STATE_SIGNALLOSS (1 << 1)
69 #define SBUS_FRAME_SIZE (SBUS_CHANNEL_DATA_LENGTH + 2)
71 #define SBUS_FRAME_BEGIN_BYTE 0x0F
73 #if !defined(SBUS_PORT_OPTIONS)
74 #define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN)
75 #endif
77 #define SBUS_DIGITAL_CHANNEL_MIN 173
78 #define SBUS_DIGITAL_CHANNEL_MAX 1812
80 enum {
81 DEBUG_SBUS_FRAME_FLAGS = 0,
82 DEBUG_SBUS_STATE_FLAGS,
83 DEBUG_SBUS_FRAME_TIME,
86 struct sbusFrame_s {
87 uint8_t syncByte;
88 sbusChannels_t channels;
89 /**
90 * The endByte is 0x00 on FrSky and some futaba RX's, on Some SBUS2 RX's the value indicates the telemetry byte that is sent after every 4th sbus frame.
92 * See https://github.com/cleanflight/cleanflight/issues/590#issuecomment-101027349
93 * and
94 * https://github.com/cleanflight/cleanflight/issues/590#issuecomment-101706023
96 uint8_t endByte;
97 } __attribute__ ((__packed__));
99 typedef union sbusFrame_u {
100 uint8_t bytes[SBUS_FRAME_SIZE];
101 struct sbusFrame_s frame;
102 } sbusFrame_t;
104 typedef struct sbusFrameData_s {
105 sbusFrame_t frame;
106 uint32_t startAtUs;
107 uint8_t position;
108 bool done;
109 } sbusFrameData_t;
111 static timeUs_t lastRcFrameTimeUs = 0;
113 // Receive ISR callback
114 static void sbusDataReceive(uint16_t c, void *data)
116 sbusFrameData_t *sbusFrameData = data;
118 const timeUs_t nowUs = microsISR();
120 const timeDelta_t sbusFrameTime = cmpTimeUs(nowUs, sbusFrameData->startAtUs);
122 if (sbusFrameTime > (long)(SBUS_TIME_NEEDED_PER_FRAME + 500)) {
123 sbusFrameData->position = 0;
126 if (sbusFrameData->position == 0) {
127 if (c != SBUS_FRAME_BEGIN_BYTE) {
128 return;
130 sbusFrameData->startAtUs = nowUs;
133 if (sbusFrameData->position < SBUS_FRAME_SIZE) {
134 sbusFrameData->frame.bytes[sbusFrameData->position++] = (uint8_t)c;
135 if (sbusFrameData->position < SBUS_FRAME_SIZE) {
136 sbusFrameData->done = false;
137 } else {
138 lastRcFrameTimeUs = nowUs;
139 sbusFrameData->done = true;
140 DEBUG_SET(DEBUG_SBUS, DEBUG_SBUS_FRAME_TIME, sbusFrameTime);
145 static uint8_t sbusFrameStatus(rxRuntimeState_t *rxRuntimeState)
147 sbusFrameData_t *sbusFrameData = rxRuntimeState->frameData;
148 if (!sbusFrameData->done) {
149 return RX_FRAME_PENDING;
151 sbusFrameData->done = false;
153 DEBUG_SET(DEBUG_SBUS, DEBUG_SBUS_FRAME_FLAGS, sbusFrameData->frame.frame.channels.flags);
155 const uint8_t frameStatus = sbusChannelsDecode(rxRuntimeState, &sbusFrameData->frame.frame.channels);
157 if (frameStatus != RX_FRAME_COMPLETE) {
158 lastRcFrameTimeUs = 0; // We received a frame but it wasn't valid new channel data
160 return frameStatus;
163 static timeUs_t sbusFrameTimeUs(void)
165 const timeUs_t result = lastRcFrameTimeUs;
166 lastRcFrameTimeUs = 0;
167 return result;
170 bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
172 static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
173 static sbusFrameData_t sbusFrameData;
174 static uint32_t sbusBaudRate;
176 rxRuntimeState->channelData = sbusChannelData;
177 rxRuntimeState->frameData = &sbusFrameData;
178 sbusChannelsInit(rxConfig, rxRuntimeState);
180 rxRuntimeState->channelCount = SBUS_MAX_CHANNEL;
182 if (rxConfig->sbus_baud_fast) {
183 rxRuntimeState->rxRefreshRate = SBUS_FAST_RX_REFRESH_RATE;
184 sbusBaudRate = SBUS_FAST_BAUDRATE;
185 } else {
186 rxRuntimeState->rxRefreshRate = SBUS_RX_REFRESH_RATE;
187 sbusBaudRate = SBUS_BAUDRATE;
190 rxRuntimeState->rcFrameStatusFn = sbusFrameStatus;
191 rxRuntimeState->rcFrameTimeUsFn = sbusFrameTimeUs;
193 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
194 if (!portConfig) {
195 return false;
198 #ifdef USE_TELEMETRY
199 bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
200 #else
201 bool portShared = false;
202 #endif
204 serialPort_t *sBusPort = openSerialPort(portConfig->identifier,
205 FUNCTION_RX_SERIAL,
206 sbusDataReceive,
207 &sbusFrameData,
208 sbusBaudRate,
209 portShared ? MODE_RXTX : MODE_RX,
210 SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
213 if (rxConfig->rssi_src_frame_errors) {
214 rssiSource = RSSI_SOURCE_FRAME_ERRORS;
217 #ifdef USE_TELEMETRY
218 if (portShared) {
219 telemetrySharedPort = sBusPort;
221 #endif
223 return sBusPort != NULL;
225 #endif