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/>.
24 FILE_COMPILE_FOR_SPEED
28 #include "build/debug.h"
30 #include "common/utils.h"
32 #include "drivers/time.h"
34 #include "io/serial.h"
37 #include "telemetry/telemetry.h"
42 #include "rx/sbus_channels.h"
48 * time between frames: 6ms.
49 * time to send frame: 3ms.
51 * Futaba R6208SB/R6303SB
52 * time between frames: 11ms.
53 * time to send frame: 3ms.
61 typedef struct sbusFrameData_s
{
62 sbusDecoderState_e state
;
63 volatile sbusFrame_t frame
;
64 volatile bool frameDone
;
65 uint8_t buffer
[SBUS_FRAME_SIZE
];
67 timeUs_t lastActivityTimeUs
;
70 // Receive ISR callback
71 static void sbusDataReceive(uint16_t c
, void *data
)
73 static uint16_t sbusDesyncCounter
= 0;
75 sbusFrameData_t
*sbusFrameData
= data
;
76 const timeUs_t currentTimeUs
= micros();
77 const timeDelta_t timeSinceLastByteUs
= cmpTimeUs(currentTimeUs
, sbusFrameData
->lastActivityTimeUs
);
78 sbusFrameData
->lastActivityTimeUs
= currentTimeUs
;
80 // 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
81 if (sbusFrameData
->state
== STATE_SBUS_WAIT_SYNC
&& timeSinceLastByteUs
>= rxConfig()->sbusSyncInterval
) {
82 sbusFrameData
->state
= STATE_SBUS_SYNC
;
85 switch (sbusFrameData
->state
) {
87 if (c
== SBUS_FRAME_BEGIN_BYTE
) {
88 sbusFrameData
->position
= 0;
89 sbusFrameData
->buffer
[sbusFrameData
->position
++] = (uint8_t)c
;
90 sbusFrameData
->state
= STATE_SBUS_PAYLOAD
;
94 case STATE_SBUS_PAYLOAD
:
95 sbusFrameData
->buffer
[sbusFrameData
->position
++] = (uint8_t)c
;
97 if (sbusFrameData
->position
== SBUS_FRAME_SIZE
) {
98 const sbusFrame_t
* frame
= (sbusFrame_t
*)&sbusFrameData
->buffer
[0];
99 bool frameValid
= false;
101 // Do some sanity check
102 switch (frame
->endByte
) {
103 case 0x00: // This is S.BUS 1
104 case 0x04: // S.BUS 2 receiver voltage
105 case 0x14: // S.BUS 2 GPS/baro
106 case 0x24: // Unknown SBUS2 data
107 case 0x34: // Unknown SBUS2 data
109 sbusFrameData
->state
= STATE_SBUS_WAIT_SYNC
;
112 default: // Failed end marker
113 sbusFrameData
->state
= STATE_SBUS_WAIT_SYNC
;
118 // Frame seems sane, pass data to decoder
119 if (!sbusFrameData
->frameDone
&& frameValid
) {
121 memcpy((void *)&sbusFrameData
->frame
, (void *)&sbusFrameData
->buffer
[0], SBUS_FRAME_SIZE
);
122 sbusFrameData
->frameDone
= true;
127 case STATE_SBUS_WAIT_SYNC
:
128 // Stay at this state and do nothing. Exit will be handled before byte is processed if the
129 // inter-frame gap is long enough
134 static uint8_t sbusFrameStatus(rxRuntimeConfig_t
*rxRuntimeConfig
)
136 sbusFrameData_t
*sbusFrameData
= rxRuntimeConfig
->frameData
;
138 if (!sbusFrameData
->frameDone
) {
139 return RX_FRAME_PENDING
;
142 // Decode channel data and store return value
143 const uint8_t retValue
= sbusChannelsDecode(rxRuntimeConfig
, (void *)&sbusFrameData
->frame
.channels
);
145 // Reset the frameDone flag - tell ISR that we're ready to receive next frame
146 sbusFrameData
->frameDone
= false;
148 // Calculate "virtual link quality based on packet loss metric"
149 if (retValue
& RX_FRAME_COMPLETE
) {
150 lqTrackerAccumulate(rxRuntimeConfig
->lqTracker
, ((retValue
& RX_FRAME_DROPPED
) || (retValue
& RX_FRAME_FAILSAFE
)) ? 0 : RSSI_MAX_VALUE
);
156 static bool sbusInitEx(const rxConfig_t
*rxConfig
, rxRuntimeConfig_t
*rxRuntimeConfig
, uint32_t sbusBaudRate
)
158 static uint16_t sbusChannelData
[SBUS_MAX_CHANNEL
];
159 static sbusFrameData_t sbusFrameData
;
161 rxRuntimeConfig
->channelData
= sbusChannelData
;
162 rxRuntimeConfig
->frameData
= &sbusFrameData
;
164 sbusChannelsInit(rxRuntimeConfig
);
166 rxRuntimeConfig
->channelCount
= SBUS_MAX_CHANNEL
;
168 rxRuntimeConfig
->rcFrameStatusFn
= sbusFrameStatus
;
170 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
176 bool portShared
= telemetryCheckRxPortShared(portConfig
);
178 bool portShared
= false;
181 serialPort_t
*sBusPort
= openSerialPort(portConfig
->identifier
,
186 portShared
? MODE_RXTX
: MODE_RX
,
188 (rxConfig
->serialrx_inverted
? 0 : SERIAL_INVERTED
) |
189 (tristateWithDefaultOffIsActive(rxConfig
->halfDuplex
) ? SERIAL_BIDIR
: 0)
194 telemetrySharedPort
= sBusPort
;
198 return sBusPort
!= NULL
;
201 bool sbusInit(const rxConfig_t
*rxConfig
, rxRuntimeConfig_t
*rxRuntimeConfig
)
203 return sbusInitEx(rxConfig
, rxRuntimeConfig
, SBUS_BAUDRATE
);
206 bool sbusInitFast(const rxConfig_t
*rxConfig
, rxRuntimeConfig_t
*rxRuntimeConfig
)
208 return sbusInitEx(rxConfig
, rxRuntimeConfig
, SBUS_BAUDRATE_FAST
);