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)
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/>.
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"
38 #include "telemetry/telemetry.h"
45 #include "rx/sbus_channels.h"
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)
77 #define SBUS_DIGITAL_CHANNEL_MIN 173
78 #define SBUS_DIGITAL_CHANNEL_MAX 1812
81 DEBUG_SBUS_FRAME_FLAGS
= 0,
82 DEBUG_SBUS_STATE_FLAGS
,
83 DEBUG_SBUS_FRAME_TIME
,
88 sbusChannels_t channels
;
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
94 * https://github.com/cleanflight/cleanflight/issues/590#issuecomment-101706023
97 } __attribute__ ((__packed__
));
99 typedef union sbusFrame_u
{
100 uint8_t bytes
[SBUS_FRAME_SIZE
];
101 struct sbusFrame_s frame
;
104 typedef struct sbusFrameData_s
{
111 // Receive ISR callback
112 static void sbusDataReceive(uint16_t c
, void *data
)
114 sbusFrameData_t
*sbusFrameData
= data
;
116 const timeUs_t nowUs
= microsISR();
118 const timeDelta_t sbusFrameTime
= cmpTimeUs(nowUs
, sbusFrameData
->startAtUs
);
120 if (sbusFrameTime
> (long)(SBUS_TIME_NEEDED_PER_FRAME
+ 500)) {
121 sbusFrameData
->position
= 0;
124 if (sbusFrameData
->position
== 0) {
125 if (c
!= SBUS_FRAME_BEGIN_BYTE
) {
128 sbusFrameData
->startAtUs
= nowUs
;
131 if (sbusFrameData
->position
< SBUS_FRAME_SIZE
) {
132 sbusFrameData
->frame
.bytes
[sbusFrameData
->position
++] = (uint8_t)c
;
133 if (sbusFrameData
->position
< SBUS_FRAME_SIZE
) {
134 sbusFrameData
->done
= false;
136 sbusFrameData
->done
= true;
137 DEBUG_SET(DEBUG_SBUS
, DEBUG_SBUS_FRAME_TIME
, sbusFrameTime
);
142 static uint8_t sbusFrameStatus(rxRuntimeState_t
*rxRuntimeState
)
144 sbusFrameData_t
*sbusFrameData
= rxRuntimeState
->frameData
;
145 if (!sbusFrameData
->done
) {
146 return RX_FRAME_PENDING
;
148 sbusFrameData
->done
= false;
150 DEBUG_SET(DEBUG_SBUS
, DEBUG_SBUS_FRAME_FLAGS
, sbusFrameData
->frame
.frame
.channels
.flags
);
152 const uint8_t frameStatus
= sbusChannelsDecode(rxRuntimeState
, &sbusFrameData
->frame
.frame
.channels
);
154 if (!(frameStatus
& (RX_FRAME_FAILSAFE
| RX_FRAME_DROPPED
))) {
155 rxRuntimeState
->lastRcFrameTimeUs
= sbusFrameData
->startAtUs
;
161 bool sbusInit(const rxConfig_t
*rxConfig
, rxRuntimeState_t
*rxRuntimeState
)
163 static uint16_t sbusChannelData
[SBUS_MAX_CHANNEL
];
164 static sbusFrameData_t sbusFrameData
;
165 static uint32_t sbusBaudRate
;
167 rxRuntimeState
->channelData
= sbusChannelData
;
168 rxRuntimeState
->frameData
= &sbusFrameData
;
169 sbusChannelsInit(rxConfig
, rxRuntimeState
);
171 rxRuntimeState
->channelCount
= SBUS_MAX_CHANNEL
;
173 if (rxConfig
->sbus_baud_fast
) {
174 rxRuntimeState
->rxRefreshRate
= SBUS_FAST_RX_REFRESH_RATE
;
175 sbusBaudRate
= SBUS_FAST_BAUDRATE
;
177 rxRuntimeState
->rxRefreshRate
= SBUS_RX_REFRESH_RATE
;
178 sbusBaudRate
= SBUS_BAUDRATE
;
181 rxRuntimeState
->rcFrameStatusFn
= sbusFrameStatus
;
182 rxRuntimeState
->rcFrameTimeUsFn
= rxFrameTimeUs
;
184 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
190 bool portShared
= telemetryCheckRxPortShared(portConfig
, rxRuntimeState
->serialrxProvider
);
192 bool portShared
= false;
195 serialPort_t
*sBusPort
= openSerialPort(portConfig
->identifier
,
200 portShared
? MODE_RXTX
: MODE_RX
,
201 SBUS_PORT_OPTIONS
| (rxConfig
->serialrx_inverted
? 0 : SERIAL_INVERTED
) | (rxConfig
->halfDuplex
? SERIAL_BIDIR
: 0)
204 if (rxConfig
->rssi_src_frame_errors
) {
205 rssiSource
= RSSI_SOURCE_FRAME_ERRORS
;
210 telemetrySharedPort
= sBusPort
;
214 return sBusPort
!= NULL
;