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(...)
56 #define SRXL2_MAX_CHANNELS 32
57 #define SRXL2_FRAME_PERIOD_US 11000 // 5500 for DSMR
58 #define SRXL2_CHANNEL_SHIFT 2
59 #define SRXL2_CHANNEL_CENTER 0x8000
61 #define SRXL2_PORT_BAUDRATE_DEFAULT 115200
62 #define SRXL2_PORT_BAUDRATE_HIGH 400000
63 #define SRXL2_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO | SERIAL_BIDIR)
64 #define SRXL2_PORT_MODE MODE_RXTX
66 #define SRXL2_REPLY_QUIESCENCE (2 * 10 * 1000000 / SRXL2_PORT_BAUDRATE_DEFAULT) // 2 * (lastIdleTimestamp - lastReceiveTimestamp). Time taken to send 2 bytes
69 #define SRXL2_MAX_PACKET_LENGTH 80
70 #define SRXL2_DEVICE_ID_BROADCAST 0xFF
72 #define SRXL2_FRAME_TIMEOUT_US 50000
74 #define SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US 50000
75 #define SRXL2_SEND_HANDSHAKE_TIMEOUT_US 50000
76 #define SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US 200000
78 #define SPEKTRUM_PULSE_OFFSET 988 // Offset value to convert digital data into RC pulse
81 uint8_t raw
[SRXL2_MAX_PACKET_LENGTH
];
86 volatile unsigned len
;
90 static uint8_t unitId
= 0;
91 static uint8_t baudRate
= 0;
93 static Srxl2State state
= Disabled
;
94 static uint32_t timeoutTimestamp
= 0;
95 static uint32_t fullTimeoutTimestamp
= 0;
96 static uint32_t lastValidPacketTimestamp
= 0;
97 static volatile uint32_t lastReceiveTimestamp
= 0;
98 static volatile uint32_t lastIdleTimestamp
= 0;
100 struct rxBuf readBuffer
[2];
101 struct rxBuf
* readBufferPtr
= &readBuffer
[0];
102 struct rxBuf
* processBufferPtr
= &readBuffer
[1];
103 static volatile unsigned readBufferIdx
= 0;
104 static volatile bool transmittingTelemetry
= false;
105 static uint8_t writeBuffer
[SRXL2_MAX_PACKET_LENGTH
];
106 static unsigned writeBufferIdx
= 0;
108 static serialPort_t
*serialPort
;
110 static uint8_t busMasterDeviceId
= 0xFF;
111 static bool telemetryRequested
= false;
113 static uint8_t telemetryFrame
[22];
115 uint8_t globalResult
= 0;
117 /* handshake protocol
118 1. listen for 50ms for serial activity and go to State::Running if found, autobaud may be necessary
119 2. if srxl2_unitId = 0:
120 send a Handshake with destinationDeviceId = 0 every 50ms for at least 200ms
122 listen for Handshake for at least 200ms
123 3. respond to Handshake as currently implemented in process if rePst received
124 4. respond to broadcast Handshake
127 // if 50ms with not activity, go to default baudrate and to step 1
129 bool srxl2ProcessHandshake(const Srxl2Header
* header
)
131 const Srxl2HandshakeSubHeader
* handshake
= (Srxl2HandshakeSubHeader
*)(header
+ 1);
132 if (handshake
->destinationDeviceId
== Broadcast
) {
133 DEBUG_PRINTF("broadcast handshake from %x\r\n", handshake
->sourceDeviceId
);
134 busMasterDeviceId
= handshake
->sourceDeviceId
;
136 if (handshake
->baudSupported
== 1) {
137 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_HIGH
);
138 DEBUG_PRINTF("switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_HIGH
);
147 if (handshake
->destinationDeviceId
!= ((FlightController
<< 4) | unitId
)) {
151 DEBUG_PRINTF("FC handshake from %x\r\n", handshake
->sourceDeviceId
);
153 Srxl2HandshakeFrame response
= {
156 handshake
->destinationDeviceId
,
157 handshake
->sourceDeviceId
,
159 /* baudSupported*/ baudRate
,
165 srxl2RxWriteData(&response
, sizeof(response
));
170 void srxl2ProcessChannelData(const Srxl2ChannelDataHeader
* channelData
, rxRuntimeState_t
*rxRuntimeState
) {
171 globalResult
= RX_FRAME_COMPLETE
;
173 if (channelData
->rssi
>= 0) {
174 const int rssiPercent
= channelData
->rssi
;
175 setRssi(scaleRange(rssiPercent
, 0, 100, 0, RSSI_MAX_VALUE
), RSSI_SOURCE_RX_PROTOCOL
);
178 //If receiver is in a connected state, and a packet is missed, the channel mask will be 0.
179 if (!channelData
->channelMask
.u32
) {
180 globalResult
|= RX_FRAME_DROPPED
;
184 const uint16_t *frameChannels
= (const uint16_t *) (channelData
+ 1);
185 uint32_t channelMask
= channelData
->channelMask
.u32
;
186 while (channelMask
) {
187 unsigned idx
= __builtin_ctz (channelMask
);
188 uint32_t mask
= 1 << idx
;
189 rxRuntimeState
->channelData
[idx
] = *frameChannels
++;
190 channelMask
&= ~mask
;
193 DEBUG_PRINTF("channel data: %d %d %x\r\n", channelData_header
->rssi
, channelData_header
->frameLosses
, channelData_header
->channelMask
.u32
);
196 bool srxl2ProcessControlData(const Srxl2Header
* header
, rxRuntimeState_t
*rxRuntimeState
)
198 const Srxl2ControlDataSubHeader
* controlData
= (Srxl2ControlDataSubHeader
*)(header
+ 1);
199 const uint8_t ownId
= (FlightController
<< 4) | unitId
;
200 if (controlData
->replyId
== ownId
) {
201 telemetryRequested
= true;
202 DEBUG_PRINTF("command: %x replyId: %x ownId: %x\r\n", controlData
->command
, controlData
->replyId
, ownId
);
205 switch (controlData
->command
) {
207 srxl2ProcessChannelData((const Srxl2ChannelDataHeader
*) (controlData
+ 1), rxRuntimeState
);
210 case FailsafeChannelData
: {
211 globalResult
|= RX_FRAME_FAILSAFE
;
212 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL
);
213 // DEBUG_PRINTF("fs channel data\r\n");
217 #if defined(USE_SPEKTRUM_VTX_CONTROL) && defined(USE_VTX_COMMON)
218 Srxl2VtxData
*vtxData
= (Srxl2VtxData
*)(controlData
+ 1);
219 DEBUG_PRINTF("vtx data\r\n");
220 DEBUG_PRINTF("vtx band: %x\r\n", vtxData
->band
);
221 DEBUG_PRINTF("vtx channel: %x\r\n", vtxData
->channel
);
222 DEBUG_PRINTF("vtx pit: %x\r\n", vtxData
->pit
);
223 DEBUG_PRINTF("vtx power: %x\r\n", vtxData
->power
);
224 DEBUG_PRINTF("vtx powerDec: %x\r\n", vtxData
->powerDec
);
225 DEBUG_PRINTF("vtx region: %x\r\n", vtxData
->region
);
226 // Pack data as it was used before srxl2 to use existing functions.
227 // Get the VTX control bytes in a frame
228 uint32_t vtxControl
= (0xE0 << 24) | (0xE0 << 8) |
229 ((vtxData
->band
& 0x07) << 21) |
230 ((vtxData
->channel
& 0x0F) << 16) |
231 ((vtxData
->pit
& 0x01) << 4) |
232 ((vtxData
->region
& 0x01) << 3) |
233 ((vtxData
->power
& 0x07));
234 spektrumHandleVtxControl(vtxControl
);
242 bool srxl2ProcessPacket(const Srxl2Header
* header
, rxRuntimeState_t
*rxRuntimeState
)
244 switch (header
->packetType
) {
246 return srxl2ProcessHandshake(header
);
248 return srxl2ProcessControlData(header
, rxRuntimeState
);
250 DEBUG_PRINTF("Other packet type, ID: %x \r\n", header
->packetType
);
257 // @note assumes packet is fully there
258 void srxl2Process(rxRuntimeState_t
*rxRuntimeState
)
260 if (processBufferPtr
->packet
.header
.id
!= SRXL2_ID
|| processBufferPtr
->len
!= processBufferPtr
->packet
.header
.length
) {
261 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
);
262 globalResult
= RX_FRAME_DROPPED
;
266 const uint16_t calculatedCrc
= crc16_ccitt_update(0, processBufferPtr
->packet
.raw
, processBufferPtr
->packet
.header
.length
);
268 //Invalid if crc non-zero
270 globalResult
= RX_FRAME_DROPPED
;
271 DEBUG_PRINTF("crc mismatch %x\r\n", calculatedCrc
);
275 //Packet is valid only after ID and CRC check out
276 lastValidPacketTimestamp
= micros();
278 if (srxl2ProcessPacket(&processBufferPtr
->packet
.header
, rxRuntimeState
)) {
282 DEBUG_PRINTF("could not parse packet: %x\r\n", processBufferPtr
->packet
.header
.packetType
);
283 globalResult
= RX_FRAME_DROPPED
;
287 static void srxl2DataReceive(uint16_t character
, void *data
)
291 lastReceiveTimestamp
= microsISR();
293 //If the buffer len is not reset for whatever reason, disable reception
294 if (readBufferPtr
->len
> 0 || readBufferIdx
>= SRXL2_MAX_PACKET_LENGTH
) {
296 globalResult
= RX_FRAME_DROPPED
;
299 readBufferPtr
->packet
.raw
[readBufferIdx
] = character
;
304 static void srxl2Idle()
306 if (transmittingTelemetry
) { // Transmitting telemetry triggers idle interrupt as well. We dont want to change buffers then
307 transmittingTelemetry
= false;
309 else if (readBufferIdx
== 0) { // Packet was invalid
310 readBufferPtr
->len
= 0;
313 lastIdleTimestamp
= microsISR();
314 //Swap read and process buffer pointers
315 if (processBufferPtr
== &readBuffer
[0]) {
316 processBufferPtr
= &readBuffer
[1];
317 readBufferPtr
= &readBuffer
[0];
319 processBufferPtr
= &readBuffer
[0];
320 readBufferPtr
= &readBuffer
[1];
322 processBufferPtr
->len
= readBufferIdx
;
328 static uint8_t srxl2FrameStatus(rxRuntimeState_t
*rxRuntimeState
)
330 UNUSED(rxRuntimeState
);
332 globalResult
= RX_FRAME_PENDING
;
334 // len should only be set after an idle interrupt (packet reception complete)
335 if (processBufferPtr
!= NULL
&& processBufferPtr
->len
) {
336 srxl2Process(rxRuntimeState
);
337 processBufferPtr
->len
= 0;
340 uint8_t result
= globalResult
;
342 const uint32_t now
= micros();
345 case Disabled
: break;
347 case ListenForActivity
: {
349 if (lastValidPacketTimestamp
!= 0) {
350 // as ListenForActivity is done at default baud-rate, we don't need to change anything
351 // @todo if there were non-handshake packets - go to running,
352 // if there were - go to either Send Handshake or Listen For Handshake
354 } else if (cmpTimeUs(lastIdleTimestamp
, lastReceiveTimestamp
) > 0) {
356 uint32_t currentBaud
= serialGetBaudRate(serialPort
);
358 if(currentBaud
== SRXL2_PORT_BAUDRATE_DEFAULT
)
359 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_HIGH
);
361 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
363 } else if (cmpTimeUs(now
, timeoutTimestamp
) >= 0) {
364 // @todo if there was activity - detect baudrate and ListenForHandshake
367 state
= SendHandshake
;
368 timeoutTimestamp
= now
+ SRXL2_SEND_HANDSHAKE_TIMEOUT_US
;
369 fullTimeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US
;
371 state
= ListenForHandshake
;
372 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US
;
377 case SendHandshake
: {
378 if (cmpTimeUs(now
, timeoutTimestamp
) >= 0) {
379 // @todo set another timeout for 50ms tries
380 // fill write buffer with handshake frame
381 result
|= RX_FRAME_PROCESSING_REQUIRED
;
384 if (cmpTimeUs(now
, fullTimeoutTimestamp
) >= 0) {
385 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
386 DEBUG_PRINTF("case SendHandshake: switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_DEFAULT
);
387 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
388 result
= (result
& ~RX_FRAME_PENDING
) | RX_FRAME_FAILSAFE
;
390 state
= ListenForActivity
;
391 lastReceiveTimestamp
= 0;
395 case ListenForHandshake
: {
396 if (cmpTimeUs(now
, timeoutTimestamp
) >= 0) {
397 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
398 DEBUG_PRINTF("case ListenForHandshake: switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_DEFAULT
);
399 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
400 result
= (result
& ~RX_FRAME_PENDING
) | RX_FRAME_FAILSAFE
;
402 state
= ListenForActivity
;
403 lastReceiveTimestamp
= 0;
408 // frame timed out, reset state
409 if (cmpTimeUs(now
, lastValidPacketTimestamp
) >= SRXL2_FRAME_TIMEOUT_US
) {
410 serialSetBaudRate(serialPort
, SRXL2_PORT_BAUDRATE_DEFAULT
);
411 DEBUG_PRINTF("case Running: switching to %d baud: %d %d\r\n", SRXL2_PORT_BAUDRATE_DEFAULT
, now
, lastValidPacketTimestamp
);
412 timeoutTimestamp
= now
+ SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
413 result
= (result
& ~RX_FRAME_PENDING
) | RX_FRAME_FAILSAFE
;
415 state
= ListenForActivity
;
416 lastReceiveTimestamp
= 0;
417 lastValidPacketTimestamp
= 0;
422 if (writeBufferIdx
) {
423 result
|= RX_FRAME_PROCESSING_REQUIRED
;
426 if (!(result
& (RX_FRAME_FAILSAFE
| RX_FRAME_DROPPED
))) {
427 rxRuntimeState
->lastRcFrameTimeUs
= lastIdleTimestamp
;
433 static bool srxl2ProcessFrame(const rxRuntimeState_t
*rxRuntimeState
)
435 UNUSED(rxRuntimeState
);
437 if (writeBufferIdx
== 0) {
441 const uint32_t now
= micros();
443 if (cmpTimeUs(lastIdleTimestamp
, lastReceiveTimestamp
) > 0) {
444 // time sufficient for at least 2 characters has passed
445 if (cmpTimeUs(now
, lastReceiveTimestamp
) > SRXL2_REPLY_QUIESCENCE
) {
446 transmittingTelemetry
= true;
447 serialWriteBuf(serialPort
, writeBuffer
, writeBufferIdx
);
450 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
);
453 DEBUG_PRINTF("still receiving a frame, %d %d\r\n", lastIdleTimestamp
, lastReceiveTimestamp
);
459 static float srxl2ReadRawRC(const rxRuntimeState_t
*rxRuntimeState
, uint8_t channelIdx
)
461 if (channelIdx
>= rxRuntimeState
->channelCount
) {
465 return ((float)(rxRuntimeState
->channelData
[channelIdx
] >> SRXL2_CHANNEL_SHIFT
) / 16) + SPEKTRUM_PULSE_OFFSET
;
468 void srxl2RxWriteData(const void *data
, int len
)
470 const uint16_t crc
= crc16_ccitt_update(0, (uint8_t*)data
, len
- 2);
471 ((uint8_t*)data
)[len
-2] = ((uint8_t *) &crc
)[1] & 0xFF;
472 ((uint8_t*)data
)[len
-1] = ((uint8_t *) &crc
)[0] & 0xFF;
474 len
= MIN(len
, (int)sizeof(writeBuffer
));
475 memcpy(writeBuffer
, data
, len
);
476 writeBufferIdx
= len
;
479 bool srxl2RxInit(const rxConfig_t
*rxConfig
, rxRuntimeState_t
*rxRuntimeState
)
481 static uint16_t channelData
[SRXL2_MAX_CHANNELS
];
482 for (size_t i
= 0; i
< SRXL2_MAX_CHANNELS
; ++i
) {
483 channelData
[i
] = SRXL2_CHANNEL_CENTER
;
486 unitId
= rxConfig
->srxl2_unit_id
;
487 baudRate
= rxConfig
->srxl2_baud_fast
;
489 rxRuntimeState
->channelData
= channelData
;
490 rxRuntimeState
->channelCount
= SRXL2_MAX_CHANNELS
;
491 rxRuntimeState
->rxRefreshRate
= SRXL2_FRAME_PERIOD_US
;
493 rxRuntimeState
->rcReadRawFn
= srxl2ReadRawRC
;
494 rxRuntimeState
->rcFrameStatusFn
= srxl2FrameStatus
;
495 rxRuntimeState
->rcFrameTimeUsFn
= rxFrameTimeUs
;
496 rxRuntimeState
->rcProcessFrameFn
= srxl2ProcessFrame
;
498 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
503 portOptions_e options
= SRXL2_PORT_OPTIONS
;
504 if (rxConfig
->serialrx_inverted
) {
505 options
|= SERIAL_INVERTED
;
507 if (rxConfig
->halfDuplex
) {
508 options
|= SERIAL_BIDIR
;
511 serialPort
= openSerialPort(portConfig
->identifier
, FUNCTION_RX_SERIAL
, srxl2DataReceive
,
512 NULL
, SRXL2_PORT_BAUDRATE_DEFAULT
, SRXL2_PORT_MODE
, options
);
518 serialPort
->idleCallback
= srxl2Idle
;
520 state
= ListenForActivity
;
521 timeoutTimestamp
= micros() + SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US
;
523 if (rssiSource
== RSSI_SOURCE_NONE
) {
524 rssiSource
= RSSI_SOURCE_RX_PROTOCOL
;
527 return (bool)serialPort
;
530 bool srxl2RxIsActive(void)
535 bool srxl2TelemetryRequested(void)
537 return telemetryRequested
;
540 void srxl2InitializeFrame(sbuf_t
*dst
)
542 dst
->ptr
= telemetryFrame
;
543 dst
->end
= ARRAYEND(telemetryFrame
);
545 sbufWriteU8(dst
, SRXL2_ID
);
546 sbufWriteU8(dst
, TelemetrySensorData
);
547 sbufWriteU8(dst
, ARRAYLEN(telemetryFrame
));
548 sbufWriteU8(dst
, busMasterDeviceId
);
551 void srxl2FinalizeFrame(sbuf_t
*dst
)
553 sbufSwitchToReader(dst
, telemetryFrame
);
554 // Include 2 additional bytes of length since we're letting the srxl2RxWriteData function add the CRC in
555 srxl2RxWriteData(sbufPtr(dst
), sbufBytesRemaining(dst
) + 2);
556 telemetryRequested
= false;
561 const size_t length
= sizeof(Srxl2BindInfoFrame
);
563 Srxl2BindInfoFrame bind
= {
566 .packetType
= BindInfo
,
570 .request
= EnterBindMode
,
571 .deviceId
= busMasterDeviceId
,
572 .bindType
= DMSX_11ms
,
573 .options
= SRXL_BIND_OPT_TELEM_TX_ENABLE
| SRXL_BIND_OPT_BIND_TX_ENABLE
,
577 srxl2RxWriteData(&bind
, length
);