Merge branch 'master' into abo_waypoint_tracking
[inav.git] / src / main / rx / srxl2.c
blob8a615039f3221aee12047e95ceb2efbfa26dcac6
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 <string.h>
23 #include "platform.h"
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"
38 #include "rx/srxl2.h"
39 #include "rx/srxl2_types.h"
41 #ifndef SRXL2_DEBUG
42 #define SRXL2_DEBUG 0
43 #endif
45 #if SRXL2_DEBUG
46 //void cliPrintf(const char *format, ...);
47 //#define DEBUG_PRINTF(format, ...) cliPrintf(format, __VA_ARGS__)
48 #define DEBUG_PRINTF(...) //Temporary until a better debug printf can be included
49 #else
50 #define DEBUG_PRINTF(...)
51 #endif
55 #define SRXL2_MAX_CHANNELS 32
56 #define SRXL2_FRAME_PERIOD_US 11000 // 5500 for DSMR
57 #define SRXL2_CHANNEL_SHIFT 5
58 #define SRXL2_CHANNEL_CENTER 0x8000
60 #define SRXL2_PORT_BAUDRATE_DEFAULT 115200
61 #define SRXL2_PORT_BAUDRATE_HIGH 400000
62 #define SRXL2_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO | SERIAL_BIDIR)
63 #define SRXL2_PORT_MODE MODE_RXTX
65 #define SRXL2_REPLY_QUIESCENCE (2 * 10 * 1000000 / SRXL2_PORT_BAUDRATE_DEFAULT) // 2 * (lastIdleTimestamp - lastReceiveTimestamp). Time taken to send 2 bytes
67 #define SRXL2_ID 0xA6
68 #define SRXL2_MAX_PACKET_LENGTH 80
69 #define SRXL2_DEVICE_ID_BROADCAST 0xFF
71 #define SRXL2_FRAME_TIMEOUT_US 50000
73 #define SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US 50000
74 #define SRXL2_SEND_HANDSHAKE_TIMEOUT_US 50000
75 #define SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US 200000
77 #define SPEKTRUM_PULSE_OFFSET 988 // Offset value to convert digital data into RC pulse
79 typedef union {
80 uint8_t raw[SRXL2_MAX_PACKET_LENGTH];
81 Srxl2Header header;
82 } Srxl2Frame;
84 struct rxBuf {
85 volatile unsigned len;
86 Srxl2Frame packet;
89 static uint8_t unitId = 0;
90 static uint8_t baudRate = 0;
92 static Srxl2State state = Disabled;
93 static uint32_t timeoutTimestamp = 0;
94 static uint32_t fullTimeoutTimestamp = 0;
95 static uint32_t lastValidPacketTimestamp = 0;
96 static volatile uint32_t lastReceiveTimestamp = 0;
97 static volatile uint32_t lastIdleTimestamp = 0;
99 struct rxBuf readBuffer[2];
100 struct rxBuf* readBufferPtr = &readBuffer[0];
101 struct rxBuf* processBufferPtr = &readBuffer[1];
102 static volatile unsigned readBufferIdx = 0;
103 static volatile bool transmittingTelemetry = false;
104 static uint8_t writeBuffer[SRXL2_MAX_PACKET_LENGTH];
105 static unsigned writeBufferIdx = 0;
107 static serialPort_t *serialPort;
109 static uint8_t busMasterDeviceId = 0xFF;
110 static bool telemetryRequested = false;
112 static uint8_t telemetryFrame[22];
114 uint8_t globalResult = 0;
116 /* handshake protocol
117 1. listen for 50ms for serial activity and go to State::Running if found, autobaud may be necessary
118 2. if srxl2_unitId = 0:
119 send a Handshake with destinationDeviceId = 0 every 50ms for at least 200ms
120 else:
121 listen for Handshake for at least 200ms
122 3. respond to Handshake as currently implemented in process if rePst received
123 4. respond to broadcast Handshake
126 // if 50ms with not activity, go to default baudrate and to step 1
128 bool srxl2ProcessHandshake(const Srxl2Header* header)
130 const Srxl2HandshakeSubHeader* handshake = (Srxl2HandshakeSubHeader*)(header + 1);
131 if (handshake->destinationDeviceId == Broadcast) {
132 DEBUG_PRINTF("broadcast handshake from %x\r\n", handshake->sourceDeviceId);
133 busMasterDeviceId = handshake->sourceDeviceId;
135 if (handshake->baudSupported == 1) {
136 serialSetBaudRate(serialPort, SRXL2_PORT_BAUDRATE_HIGH);
137 DEBUG_PRINTF("switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_HIGH);
140 state = Running;
142 return true;
146 if (handshake->destinationDeviceId != ((FlightController << 4) | unitId)) {
147 return true;
150 DEBUG_PRINTF("FC handshake from %x\r\n", handshake->sourceDeviceId);
152 Srxl2HandshakeFrame response = {
153 .header = *header,
154 .payload = {
155 handshake->destinationDeviceId,
156 handshake->sourceDeviceId,
157 /* priority */ 10,
158 /* baudSupported*/ baudRate,
159 /* info */ 0,
160 // U_ID_2
164 srxl2RxWriteData(&response, sizeof(response));
166 return true;
169 void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntimeConfig_t *rxRuntimeConfig) {
170 globalResult = RX_FRAME_COMPLETE;
172 if (channelData->rssi >= 0) {
173 const int rssiPercent = channelData->rssi;
174 lqTrackerSet(rxRuntimeConfig->lqTracker, scaleRange(constrain(rssiPercent, 0, 100), 0, 100, 0, RSSI_MAX_VALUE));
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_FAILSAFE;
181 return;
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 rxRuntimeConfig->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, rxRuntimeConfig_t *rxRuntimeConfig)
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) {
206 case ChannelData:
207 srxl2ProcessChannelData((const Srxl2ChannelDataHeader *) (controlData + 1), rxRuntimeConfig);
208 break;
210 case FailsafeChannelData: {
211 globalResult |= RX_FRAME_FAILSAFE;
212 //setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
213 lqTrackerSet(rxRuntimeConfig->lqTracker, 0);
214 // DEBUG_PRINTF("fs channel data\r\n");
215 } break;
217 case VTXData: {
218 #if defined(USE_SPEKTRUM_VTX_CONTROL) && defined(USE_VTX_COMMON)
219 Srxl2VtxData *vtxData = (Srxl2VtxData*)(controlData + 1);
220 DEBUG_PRINTF("vtx data\r\n");
221 DEBUG_PRINTF("vtx band: %x\r\n", vtxData->band);
222 DEBUG_PRINTF("vtx channel: %x\r\n", vtxData->channel);
223 DEBUG_PRINTF("vtx pit: %x\r\n", vtxData->pit);
224 DEBUG_PRINTF("vtx power: %x\r\n", vtxData->power);
225 DEBUG_PRINTF("vtx powerDec: %x\r\n", vtxData->powerDec);
226 DEBUG_PRINTF("vtx region: %x\r\n", vtxData->region);
227 // Pack data as it was used before srxl2 to use existing functions.
228 // Get the VTX control bytes in a frame
229 uint32_t vtxControl = (0xE0 << 24) | (0xE0 << 8) |
230 ((vtxData->band & 0x07) << 21) |
231 ((vtxData->channel & 0x0F) << 16) |
232 ((vtxData->pit & 0x01) << 4) |
233 ((vtxData->region & 0x01) << 3) |
234 ((vtxData->power & 0x07));
235 spektrumHandleVtxControl(vtxControl);
236 #endif
237 } break;
240 return true;
243 bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeConfig_t *rxRuntimeConfig)
245 switch (header->packetType) {
246 case Handshake:
247 return srxl2ProcessHandshake(header);
248 case ControlData:
249 return srxl2ProcessControlData(header, rxRuntimeConfig);
250 default:
251 DEBUG_PRINTF("Other packet type, ID: %x \r\n", header->packetType);
252 break;
255 return false;
258 // @note assumes packet is fully there
259 void srxl2Process(rxRuntimeConfig_t *rxRuntimeConfig)
261 if (processBufferPtr->packet.header.id != SRXL2_ID || processBufferPtr->len != processBufferPtr->packet.header.length) {
262 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);
263 globalResult = RX_FRAME_DROPPED;
264 return;
267 const uint16_t calculatedCrc = crc16_ccitt_update(0, processBufferPtr->packet.raw, processBufferPtr->packet.header.length);
269 //Invalid if crc non-zero
270 if (calculatedCrc) {
271 globalResult = RX_FRAME_DROPPED;
272 DEBUG_PRINTF("crc mismatch %x\r\n", calculatedCrc);
273 return;
276 //Packet is valid only after ID and CRC check out
277 lastValidPacketTimestamp = micros();
279 if (srxl2ProcessPacket(&processBufferPtr->packet.header, rxRuntimeConfig)) {
280 return;
283 DEBUG_PRINTF("could not parse packet: %x\r\n", processBufferPtr->packet.header.packetType);
284 globalResult = RX_FRAME_DROPPED;
288 static void srxl2DataReceive(uint16_t character, void *data)
290 UNUSED(data);
292 lastReceiveTimestamp = microsISR();
294 //If the buffer len is not reset for whatever reason, disable reception
295 if (readBufferPtr->len > 0 || readBufferIdx >= SRXL2_MAX_PACKET_LENGTH) {
296 readBufferIdx = 0;
297 globalResult = RX_FRAME_DROPPED;
299 else {
300 readBufferPtr->packet.raw[readBufferIdx] = character;
301 readBufferIdx++;
305 static void srxl2Idle(void)
307 if(transmittingTelemetry) { // Transmitting telemetry triggers idle interrupt as well. We dont want to change buffers then
308 transmittingTelemetry = false;
310 else if(readBufferIdx == 0) { // Packet was invalid
311 readBufferPtr->len = 0;
313 else {
314 lastIdleTimestamp = microsISR();
315 //Swap read and process buffer pointers
316 if(processBufferPtr == &readBuffer[0]) {
317 processBufferPtr = &readBuffer[1];
318 readBufferPtr = &readBuffer[0];
319 } else {
320 processBufferPtr = &readBuffer[0];
321 readBufferPtr = &readBuffer[1];
323 processBufferPtr->len = readBufferIdx;
326 readBufferIdx = 0;
329 static uint8_t srxl2FrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
331 UNUSED(rxRuntimeConfig);
333 if(serialIsIdle(serialPort))
335 srxl2Idle();
338 globalResult = RX_FRAME_PENDING;
340 // len should only be set after an idle interrupt (packet reception complete)
341 if (processBufferPtr != NULL && processBufferPtr->len) {
342 srxl2Process(rxRuntimeConfig);
343 processBufferPtr->len = 0;
346 uint8_t result = globalResult;
348 const uint32_t now = micros();
350 switch (state) {
351 case Disabled: break;
353 case ListenForActivity: {
354 // activity detected
355 if (lastValidPacketTimestamp != 0) {
356 // as ListenForActivity is done at default baud-rate, we don't need to change anything
357 // @todo if there were non-handshake packets - go to running,
358 // if there were - go to either Send Handshake or Listen For Handshake
359 state = Running;
360 } else if (cmpTimeUs(lastIdleTimestamp, lastReceiveTimestamp) > 0) {
361 if (baudRate != 0) {
362 uint32_t currentBaud = serialGetBaudRate(serialPort);
364 if(currentBaud == SRXL2_PORT_BAUDRATE_DEFAULT)
365 serialSetBaudRate(serialPort, SRXL2_PORT_BAUDRATE_HIGH);
366 else
367 serialSetBaudRate(serialPort, SRXL2_PORT_BAUDRATE_DEFAULT);
369 } else if (cmpTimeUs(now, timeoutTimestamp) >= 0) {
370 // @todo if there was activity - detect baudrate and ListenForHandshake
372 if (unitId == 0) {
373 state = SendHandshake;
374 timeoutTimestamp = now + SRXL2_SEND_HANDSHAKE_TIMEOUT_US;
375 fullTimeoutTimestamp = now + SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US;
376 } else {
377 state = ListenForHandshake;
378 timeoutTimestamp = now + SRXL2_LISTEN_FOR_HANDSHAKE_TIMEOUT_US;
381 } break;
383 case SendHandshake: {
384 if (cmpTimeUs(now, timeoutTimestamp) >= 0) {
385 // @todo set another timeout for 50ms tries
386 // fill write buffer with handshake frame
387 result |= RX_FRAME_PROCESSING_REQUIRED;
390 if (cmpTimeUs(now, fullTimeoutTimestamp) >= 0) {
391 serialSetBaudRate(serialPort, SRXL2_PORT_BAUDRATE_DEFAULT);
392 DEBUG_PRINTF("case SendHandshake: switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_DEFAULT);
393 timeoutTimestamp = now + SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US;
394 result = (result & ~RX_FRAME_PENDING) | RX_FRAME_FAILSAFE;
396 state = ListenForActivity;
397 lastReceiveTimestamp = 0;
399 } break;
401 case ListenForHandshake: {
402 if (cmpTimeUs(now, timeoutTimestamp) >= 0) {
403 serialSetBaudRate(serialPort, SRXL2_PORT_BAUDRATE_DEFAULT);
404 DEBUG_PRINTF("case ListenForHandshake: switching to %d baud\r\n", SRXL2_PORT_BAUDRATE_DEFAULT);
405 timeoutTimestamp = now + SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US;
406 result = (result & ~RX_FRAME_PENDING) | RX_FRAME_FAILSAFE;
408 state = ListenForActivity;
409 lastReceiveTimestamp = 0;
411 } break;
413 case Running: {
414 // frame timed out, reset state
415 if (cmpTimeUs(now, lastValidPacketTimestamp) >= SRXL2_FRAME_TIMEOUT_US) {
416 serialSetBaudRate(serialPort, SRXL2_PORT_BAUDRATE_DEFAULT);
417 DEBUG_PRINTF("case Running: switching to %d baud: %d %d\r\n", SRXL2_PORT_BAUDRATE_DEFAULT, now, lastValidPacketTimestamp);
418 timeoutTimestamp = now + SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US;
419 result = (result & ~RX_FRAME_PENDING) | RX_FRAME_FAILSAFE;
421 state = ListenForActivity;
422 lastReceiveTimestamp = 0;
423 lastValidPacketTimestamp = 0;
425 } break;
428 if (writeBufferIdx) {
429 result |= RX_FRAME_PROCESSING_REQUIRED;
432 return result;
435 static bool srxl2ProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
437 UNUSED(rxRuntimeConfig);
439 if (writeBufferIdx == 0) {
440 return true;
443 const uint32_t now = micros();
445 if (cmpTimeUs(lastIdleTimestamp, lastReceiveTimestamp) > 0) {
446 // time sufficient for at least 2 characters has passed
447 if (cmpTimeUs(now, lastReceiveTimestamp) > SRXL2_REPLY_QUIESCENCE) {
448 transmittingTelemetry = true;
449 serialWriteBuf(serialPort, writeBuffer, writeBufferIdx);
450 writeBufferIdx = 0;
451 } else {
452 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);
454 } else {
455 DEBUG_PRINTF("still receiving a frame, %d %d\r\n", lastIdleTimestamp, lastReceiveTimestamp);
458 return true;
461 static uint16_t srxl2ReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channelIdx)
463 if (channelIdx >= rxRuntimeConfig->channelCount) {
464 return 0;
467 return SPEKTRUM_PULSE_OFFSET + ((rxRuntimeConfig->channelData[channelIdx] >> SRXL2_CHANNEL_SHIFT) >> 1);
470 void srxl2RxWriteData(const void *data, int len)
472 const uint16_t crc = crc16_ccitt_update(0, (uint8_t*)data, len - 2);
473 ((uint8_t*)data)[len-2] = ((uint8_t *) &crc)[1] & 0xFF;
474 ((uint8_t*)data)[len-1] = ((uint8_t *) &crc)[0] & 0xFF;
476 len = MIN(len, (int)sizeof(writeBuffer));
477 memcpy(writeBuffer, data, len);
478 writeBufferIdx = len;
481 bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
483 static uint16_t channelData[SRXL2_MAX_CHANNELS];
484 for (size_t i = 0; i < SRXL2_MAX_CHANNELS; ++i) {
485 channelData[i] = SRXL2_CHANNEL_CENTER;
488 unitId = rxConfig->srxl2_unit_id;
489 baudRate = rxConfig->srxl2_baud_fast;
491 rxRuntimeConfig->channelData = channelData;
492 rxRuntimeConfig->channelCount = SRXL2_MAX_CHANNELS;
493 rxRuntimeConfig->rcReadRawFn = srxl2ReadRawRC;
494 rxRuntimeConfig->rcFrameStatusFn = srxl2FrameStatus;
495 rxRuntimeConfig->rcProcessFrameFn = srxl2ProcessFrame;
497 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
498 if (!portConfig) {
499 return false;
502 portOptions_t options = SRXL2_PORT_OPTIONS;
503 if (rxConfig->serialrx_inverted) {
504 options |= SERIAL_INVERTED;
506 if (rxConfig->halfDuplex) {
507 options |= SERIAL_BIDIR;
510 serialPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, srxl2DataReceive,
511 NULL, SRXL2_PORT_BAUDRATE_DEFAULT, SRXL2_PORT_MODE, options);
513 if (!serialPort) {
514 return false;
517 state = ListenForActivity;
518 timeoutTimestamp = micros() + SRXL2_LISTEN_FOR_ACTIVITY_TIMEOUT_US;
520 //Looks like this needs to be set in cli config
521 //if (rssiSource == RSSI_SOURCE_NONE) {
522 // rssiSource = RSSI_SOURCE_RX_PROTOCOL;
525 return (bool)serialPort;
528 bool srxl2RxIsActive(void)
530 return serialPort;
533 bool srxl2TelemetryRequested(void)
535 return telemetryRequested;
538 void srxl2InitializeFrame(sbuf_t *dst)
540 dst->ptr = telemetryFrame;
541 dst->end = ARRAYEND(telemetryFrame);
543 sbufWriteU8(dst, SRXL2_ID);
544 sbufWriteU8(dst, TelemetrySensorData);
545 sbufWriteU8(dst, ARRAYLEN(telemetryFrame));
546 sbufWriteU8(dst, busMasterDeviceId);
549 void srxl2FinalizeFrame(sbuf_t *dst)
551 sbufSwitchToReader(dst, telemetryFrame);
552 // Include 2 additional bytes of length since we're letting the srxl2RxWriteData function add the CRC in
553 srxl2RxWriteData(sbufPtr(dst), sbufBytesRemaining(dst) + 2);
554 telemetryRequested = false;
557 void srxl2Bind(void)
559 const size_t length = sizeof(Srxl2BindInfoFrame);
561 Srxl2BindInfoFrame bind = {
562 .header = {
563 .id = SRXL2_ID,
564 .packetType = BindInfo,
565 .length = length
567 .payload = {
568 .request = EnterBindMode,
569 .deviceId = busMasterDeviceId,
570 .bindType = DMSX_11ms,
571 .options = SRXL_BIND_OPT_TELEM_TX_ENABLE | SRXL_BIND_OPT_BIND_TX_ENABLE,
575 srxl2RxWriteData(&bind, length);
578 #endif