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/>.
25 #ifdef USE_SERIALRX_SRXL2
27 #include "common/crc.h"
28 #include "common/maths.h"
29 #include "common/streambuf.h"
31 #include "drivers/nvic.h"
32 #include "drivers/time.h"
33 #include "drivers/serial.h"
34 #include "drivers/serial_uart.h"
36 #include "io/serial.h"
39 #include "rx/srxl2_types.h"
40 #include "io/spektrum_vtx_control.h"
47 //void cliPrintf(const char *format, ...);
48 //#define DEBUG_PRINTF(format, ...) cliPrintf(format, __VA_ARGS__)
49 #define DEBUG_PRINTF(...) //Temporary until a better debug printf can be included
51 #define DEBUG_PRINTF(...)
54 #define SRXL2_MAX_CHANNELS 32
55 #define SRXL2_FRAME_PERIOD_US 11000 // 5500 for DSMR
56 #define SRXL2_CHANNEL_SHIFT 2
57 #define SRXL2_CHANNEL_CENTER 0x8000
59 #define SRXL2_PORT_BAUDRATE_DEFAULT 115200
60 #define SRXL2_PORT_BAUDRATE_HIGH 400000
61 #define SRXL2_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO | SERIAL_BIDIR)
62 #define SRXL2_PORT_MODE MODE_RXTX
64 #define SRXL2_REPLY_QUIESCENCE (2 * 10 * 1000000 / SRXL2_PORT_BAUDRATE_DEFAULT) // 2 * (lastIdleTimestamp - lastReceiveTimestamp). Time taken to send 2 bytes
67 #define SRXL2_MAX_PACKET_LENGTH 80
68 #define SRXL2_DEVICE_ID_BROADCAST 0xFF
70 #define SRXL2_FRAME_TIMEOUT_US 50000
72 #define SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US 50000
73 #define SRXL2_SEND_HANDSHAKE_TIMEOUT_US 50000
74 #define SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US 200000
76 #define SPEKTRUM_PULSE_OFFSET 988 // Offset value to convert digital data into RC pulse
79 uint8_t raw
[SRXL2_MAX_PACKET_LENGTH
];
84 volatile unsigned len
;
88 static uint8_t unitId
= 0;
89 static uint8_t baudRate
= 0;
91 static Srxl2State state
= Disabled
;
92 static uint32_t timeoutTimestamp
= 0;
93 static uint32_t fullTimeoutTimestamp
= 0;
94 static uint32_t lastValidPacketTimestamp
= 0;
95 static volatile uint32_t lastReceiveTimestamp
= 0;
96 static volatile uint32_t lastIdleTimestamp
= 0;
98 struct rxBuf readBuffer
[2];
99 struct rxBuf
* readBufferPtr
= &readBuffer
[0];
100 struct rxBuf
* processBufferPtr
= &readBuffer
[1];
101 static volatile unsigned readBufferIdx
= 0;
102 static volatile bool transmittingTelemetry
= false;
103 static uint8_t writeBuffer
[SRXL2_MAX_PACKET_LENGTH
];
104 static unsigned writeBufferIdx
= 0;
106 static serialPort_t
*serialPort
;
108 static uint8_t busMasterDeviceId
= 0xFF;
109 static bool telemetryRequested
= false;
111 static uint8_t telemetryFrame
[22];
113 uint8_t globalResult
= 0;
115 /* handshake protocol
116 1. listen for 50ms for serial activity and go to State::Running if found, autobaud may be necessary
117 2. if srxl2_unitId = 0:
118 send a Handshake with destinationDeviceId = 0 every 50ms for at least 200ms
120 listen for Handshake for at least 200ms
121 3. respond to Handshake as currently implemented in process if rePst received
122 4. respond to broadcast Handshake
125 // if 50ms with not activity, go to default baudrate and to step 1
127 bool srxl2ProcessHandshake(const Srxl2Header
* header
)
129 const Srxl2HandshakeSubHeader
* handshake
= (Srxl2HandshakeSubHeader
*)(header
+ 1);
130 if (handshake
->destinationDeviceId
== Broadcast
) {
131 DEBUG_PRINTF("broadcast handshake from %x\r\n", handshake
->sourceDeviceId
);
132 busMasterDeviceId
= handshake
->sourceDeviceId
;
134 if (handshake
->baudSupported
== 1) {
135 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_HIGH
);
136 DEBUG_PRINTF("switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_HIGH
);
144 if (handshake
->destinationDeviceId
!= ((FlightController
<< 4) | unitId
)) {
148 DEBUG_PRINTF("FC handshake from %x\r\n", handshake
->sourceDeviceId
);
150 Srxl2HandshakeFrame response
= {
153 handshake
->destinationDeviceId
,
154 handshake
->sourceDeviceId
,
156 /* baudSupported*/ baudRate
,
162 srxl2RxWriteData(&response
, sizeof(response
));
167 void srxl2ProcessChannelData(const Srxl2ChannelDataHeader
* channelData
, rxRuntimeState_t
*rxRuntimeState
)
169 globalResult
= RX_FRAME_COMPLETE
;
171 if (channelData
->rssi
>= 0) {
172 const int rssiPercent
= channelData
->rssi
;
173 setRssi(scaleRange(rssiPercent
, 0, 100, 0, RSSI_MAX_VALUE
), RSSI_SOURCE_RX_PROTOCOL
);
176 //If receiver is in a connected state, and a packet is missed, the channel mask will be 0.
177 if (!channelData
->channelMask
.u32
) {
178 globalResult
|= RX_FRAME_DROPPED
;
182 const uint16_t *frameChannels
= (const uint16_t *) (channelData
+ 1);
183 uint32_t channelMask
= channelData
->channelMask
.u32
;
184 while (channelMask
) {
185 unsigned idx
= __builtin_ctz (channelMask
);
186 uint32_t mask
= 1 << idx
;
187 rxRuntimeState
->channelData
[idx
] = *frameChannels
++;
188 channelMask
&= ~mask
;
191 DEBUG_PRINTF("channel data: %d %d %x\r\n", channelData_header
->rssi
, channelData_header
->frameLosses
, channelData_header
->channelMask
.u32
);
194 bool srxl2ProcessControlData(const Srxl2Header
* header
, rxRuntimeState_t
*rxRuntimeState
)
196 const Srxl2ControlDataSubHeader
* controlData
= (Srxl2ControlDataSubHeader
*)(header
+ 1);
197 const uint8_t ownId
= (FlightController
<< 4) | unitId
;
198 if (controlData
->replyId
== ownId
) {
199 telemetryRequested
= true;
200 DEBUG_PRINTF("command: %x replyId: %x ownId: %x\r\n", controlData
->command
, controlData
->replyId
, ownId
);
203 switch (controlData
->command
) {
205 srxl2ProcessChannelData((const Srxl2ChannelDataHeader
*) (controlData
+ 1), rxRuntimeState
);
208 case FailsafeChannelData
: {
209 globalResult
|= RX_FRAME_FAILSAFE
;
210 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL
);
211 // DEBUG_PRINTF("fs channel data\r\n");
215 #if defined(USE_SPEKTRUM_VTX_CONTROL) && defined(USE_VTX_COMMON)
216 Srxl2VtxData
*vtxData
= (Srxl2VtxData
*)(controlData
+ 1);
217 DEBUG_PRINTF("vtx data\r\n");
218 DEBUG_PRINTF("vtx band: %x\r\n", vtxData
->band
);
219 DEBUG_PRINTF("vtx channel: %x\r\n", vtxData
->channel
);
220 DEBUG_PRINTF("vtx pit: %x\r\n", vtxData
->pit
);
221 DEBUG_PRINTF("vtx power: %x\r\n", vtxData
->power
);
222 DEBUG_PRINTF("vtx powerDec: %x\r\n", vtxData
->powerDec
);
223 DEBUG_PRINTF("vtx region: %x\r\n", vtxData
->region
);
224 // Pack data as it was used before srxl2 to use existing functions.
225 // Get the VTX control bytes in a frame
226 uint32_t vtxControl
= (0xE0U
<< 24) | (0xE0 << 8) |
227 ((vtxData
->band
& 0x07) << 21) |
228 ((vtxData
->channel
& 0x0F) << 16) |
229 ((vtxData
->pit
& 0x01) << 4) |
230 ((vtxData
->region
& 0x01) << 3) |
231 ((vtxData
->power
& 0x07));
232 spektrumHandleVtxControl(vtxControl
);
240 bool srxl2ProcessPacket(const Srxl2Header
* header
, rxRuntimeState_t
*rxRuntimeState
)
242 switch (header
->packetType
) {
244 return srxl2ProcessHandshake(header
);
246 return srxl2ProcessControlData(header
, rxRuntimeState
);
248 DEBUG_PRINTF("Other packet type, ID: %x \r\n", header
->packetType
);
255 // @note assumes packet is fully there
256 void srxl2Process(rxRuntimeState_t
*rxRuntimeState
)
258 if (processBufferPtr
->packet
.header
.id
!= SRXL2_ID
|| processBufferPtr
->len
!= processBufferPtr
->packet
.header
.length
) {
259 DEBUG_PRINTF("invalid header id: %x, or length: %x received vs %x expected \r\n", processBufferPtr
->packet
.header
.id
, processBufferPtr
->len
, processBufferPtr
->packet
.header
.length
);
260 globalResult
= RX_FRAME_DROPPED
;
264 const uint16_t calculatedCrc
= crc16_ccitt_update(0, processBufferPtr
->packet
.raw
, processBufferPtr
->packet
.header
.length
);
266 //Invalid if crc non-zero
268 globalResult
= RX_FRAME_DROPPED
;
269 DEBUG_PRINTF("crc mismatch %x\r\n", calculatedCrc
);
273 //Packet is valid only after ID and CRC check out
274 lastValidPacketTimestamp
= micros();
276 if (srxl2ProcessPacket(&processBufferPtr
->packet
.header
, rxRuntimeState
)) {
280 DEBUG_PRINTF("could not parse packet: %x\r\n", processBufferPtr
->packet
.header
.packetType
);
281 globalResult
= RX_FRAME_DROPPED
;
284 static void srxl2DataReceive(uint16_t character
, void *data
)
288 lastReceiveTimestamp
= microsISR();
290 //If the buffer len is not reset for whatever reason, disable reception
291 if (readBufferPtr
->len
> 0 || readBufferIdx
>= SRXL2_MAX_PACKET_LENGTH
) {
293 globalResult
= RX_FRAME_DROPPED
;
296 readBufferPtr
->packet
.raw
[readBufferIdx
] = character
;
301 static void srxl2Idle(void)
303 if (transmittingTelemetry
) { // Transmitting telemetry triggers idle interrupt as well. We dont want to change buffers then
304 transmittingTelemetry
= false;
306 else if (readBufferIdx
== 0) { // Packet was invalid
307 readBufferPtr
->len
= 0;
310 lastIdleTimestamp
= microsISR();
311 //Swap read and process buffer pointers
312 if (processBufferPtr
== &readBuffer
[0]) {
313 processBufferPtr
= &readBuffer
[1];
314 readBufferPtr
= &readBuffer
[0];
316 processBufferPtr
= &readBuffer
[0];
317 readBufferPtr
= &readBuffer
[1];
319 processBufferPtr
->len
= readBufferIdx
;
325 static uint8_t srxl2FrameStatus(rxRuntimeState_t
*rxRuntimeState
)
327 UNUSED(rxRuntimeState
);
329 globalResult
= RX_FRAME_PENDING
;
331 // len should only be set after an idle interrupt (packet reception complete)
332 if (processBufferPtr
!= NULL
&& processBufferPtr
->len
) {
333 srxl2Process(rxRuntimeState
);
334 processBufferPtr
->len
= 0;
337 uint8_t result
= globalResult
;
339 const uint32_t now
= micros();
342 case Disabled
: break;
344 case ListenForActivity
: {
346 if (lastValidPacketTimestamp
!= 0) {
347 // as ListenForActivity is done at default baud-rate, we don't need to change anything
348 // @todo if there were non-handshake packets - go to running,
349 // if there were - go to either Send Handshake or Listen For Handshake
351 } else if (cmpTimeUs(lastIdleTimestamp
, lastReceiveTimestamp
) > 0) {
353 uint32_t currentBaud
= serialGetBaudRate(serialPort
);
355 if(currentBaud
== SRXL2_PORT_BAUDRATE_DEFAULT
)
356 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_HIGH
);
358 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
360 } else if (cmpTimeUs(now
, timeoutTimestamp
) >= 0) {
361 // @todo if there was activity - detect baudrate and ListenForHandshake
364 state
= SendHandshake
;
365 timeoutTimestamp
= now
+ SRXL2_SEND_HANDSHAKE_TIMEOUT_US
;
366 fullTimeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US
;
368 state
= ListenForHandshake
;
369 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US
;
374 case SendHandshake
: {
375 if (cmpTimeUs(now
, timeoutTimestamp
) >= 0) {
376 // @todo set another timeout for 50ms tries
377 // fill write buffer with handshake frame
378 result
|= RX_FRAME_PROCESSING_REQUIRED
;
381 if (cmpTimeUs(now
, fullTimeoutTimestamp
) >= 0) {
382 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
383 DEBUG_PRINTF("case SendHandshake: switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_DEFAULT
);
384 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
385 result
= (result
& ~RX_FRAME_PENDING
) | RX_FRAME_FAILSAFE
;
387 state
= ListenForActivity
;
388 lastReceiveTimestamp
= 0;
392 case ListenForHandshake
: {
393 if (cmpTimeUs(now
, timeoutTimestamp
) >= 0) {
394 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
395 DEBUG_PRINTF("case ListenForHandshake: switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_DEFAULT
);
396 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
397 result
= (result
& ~RX_FRAME_PENDING
) | RX_FRAME_FAILSAFE
;
399 state
= ListenForActivity
;
400 lastReceiveTimestamp
= 0;
405 // frame timed out, reset state
406 if (cmpTimeUs(now
, lastValidPacketTimestamp
) >= SRXL2_FRAME_TIMEOUT_US
) {
407 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
408 DEBUG_PRINTF("case Running: switching to %d baud: %d %d\r\n", SRXL2_PORT_BAUDRATE_DEFAULT
, now
, lastValidPacketTimestamp
);
409 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
410 result
= (result
& ~RX_FRAME_PENDING
) | RX_FRAME_FAILSAFE
;
412 state
= ListenForActivity
;
413 lastReceiveTimestamp
= 0;
414 lastValidPacketTimestamp
= 0;
419 if (writeBufferIdx
) {
420 result
|= RX_FRAME_PROCESSING_REQUIRED
;
423 if (!(result
& (RX_FRAME_FAILSAFE
| RX_FRAME_DROPPED
))) {
424 rxRuntimeState
->lastRcFrameTimeUs
= lastIdleTimestamp
;
430 static bool srxl2ProcessFrame(const rxRuntimeState_t
*rxRuntimeState
)
432 UNUSED(rxRuntimeState
);
434 if (writeBufferIdx
== 0) {
438 const uint32_t now
= micros();
440 if (cmpTimeUs(lastIdleTimestamp
, lastReceiveTimestamp
) > 0) {
441 // time sufficient for at least 2 characters has passed
442 if (cmpTimeUs(now
, lastReceiveTimestamp
) > SRXL2_REPLY_QUIESCENCE
) {
443 transmittingTelemetry
= true;
444 serialWriteBuf(serialPort
, writeBuffer
, writeBufferIdx
);
447 DEBUG_PRINTF("not enough time to send 2 characters passed yet, %d us since last receive, %d required\r\n", now
- lastReceiveTimestamp
, SRXL2_REPLY_QUIESCENCE
);
450 DEBUG_PRINTF("still receiving a frame, %d %d\r\n", lastIdleTimestamp
, lastReceiveTimestamp
);
456 static float srxl2ReadRawRC(const rxRuntimeState_t
*rxRuntimeState
, uint8_t channelIdx
)
458 if (channelIdx
>= rxRuntimeState
->channelCount
) {
462 return ((float)(rxRuntimeState
->channelData
[channelIdx
] >> SRXL2_CHANNEL_SHIFT
) / 16) + SPEKTRUM_PULSE_OFFSET
;
465 void srxl2RxWriteData(const void *data
, int len
)
467 const uint16_t crc
= crc16_ccitt_update(0, (uint8_t*)data
, len
- 2);
468 ((uint8_t*)data
)[len
-2] = ((uint8_t *) &crc
)[1] & 0xFF;
469 ((uint8_t*)data
)[len
-1] = ((uint8_t *) &crc
)[0] & 0xFF;
471 len
= MIN(len
, (int)sizeof(writeBuffer
));
472 memcpy(writeBuffer
, data
, len
);
473 writeBufferIdx
= len
;
476 bool srxl2RxInit(const rxConfig_t
*rxConfig
, rxRuntimeState_t
*rxRuntimeState
)
478 static uint16_t channelData
[SRXL2_MAX_CHANNELS
];
479 for (size_t i
= 0; i
< SRXL2_MAX_CHANNELS
; ++i
) {
480 channelData
[i
] = SRXL2_CHANNEL_CENTER
;
483 unitId
= rxConfig
->srxl2_unit_id
;
484 baudRate
= rxConfig
->srxl2_baud_fast
;
486 rxRuntimeState
->channelData
= channelData
;
487 rxRuntimeState
->channelCount
= SRXL2_MAX_CHANNELS
;
488 rxRuntimeState
->rcReadRawFn
= srxl2ReadRawRC
;
489 rxRuntimeState
->rcFrameStatusFn
= srxl2FrameStatus
;
490 rxRuntimeState
->rcProcessFrameFn
= srxl2ProcessFrame
;
492 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
497 portOptions_e options
= SRXL2_PORT_OPTIONS
;
498 if (rxConfig
->serialrx_inverted
) {
499 options
|= SERIAL_INVERTED
;
501 if (rxConfig
->halfDuplex
) {
502 options
|= SERIAL_BIDIR
;
505 serialPort
= openSerialPort(portConfig
->identifier
, FUNCTION_RX_SERIAL
, srxl2DataReceive
,
506 NULL
, SRXL2_PORT_BAUDRATE_DEFAULT
, SRXL2_PORT_MODE
, options
);
512 serialPort
->idleCallback
= srxl2Idle
;
514 state
= ListenForActivity
;
515 timeoutTimestamp
= micros() + SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
517 if (rssiSource
== RSSI_SOURCE_NONE
) {
518 rssiSource
= RSSI_SOURCE_RX_PROTOCOL
;
521 return (bool)serialPort
;
524 bool srxl2RxIsActive(void)
529 bool srxl2TelemetryRequested(void)
531 return telemetryRequested
;
534 void srxl2InitializeFrame(sbuf_t
*dst
)
536 dst
->ptr
= telemetryFrame
;
537 dst
->end
= ARRAYEND(telemetryFrame
);
539 sbufWriteU8(dst
, SRXL2_ID
);
540 sbufWriteU8(dst
, TelemetrySensorData
);
541 sbufWriteU8(dst
, ARRAYLEN(telemetryFrame
));
542 sbufWriteU8(dst
, busMasterDeviceId
);
545 void srxl2FinalizeFrame(sbuf_t
*dst
)
547 sbufSwitchToReader(dst
, telemetryFrame
);
548 // Include 2 additional bytes of length since we're letting the srxl2RxWriteData function add the CRC in
549 srxl2RxWriteData(sbufPtr(dst
), sbufBytesRemaining(dst
) + 2);
550 telemetryRequested
= false;
555 const size_t length
= sizeof(Srxl2BindInfoFrame
);
557 Srxl2BindInfoFrame bind
= {
560 .packetType
= BindInfo
,
564 .request
= EnterBindMode
,
565 .deviceId
= busMasterDeviceId
,
566 .bindType
= DMSX_11ms
,
567 .options
= SRXL_BIND_OPT_TELEM_TX_ENABLE
| SRXL_BIND_OPT_BIND_TX_ENABLE
,
571 srxl2RxWriteData(&bind
, length
);