Removing SX1280 specific target (#11966)
[betaflight.git] / src / main / rx / crsf.c
blob0d5c2951d8052b94227936c0c133d99045ac0879
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 <stdbool.h>
22 #include <stdint.h>
23 #include <stdlib.h>
24 #include <string.h>
26 #include "platform.h"
28 #ifdef USE_SERIALRX_CRSF
30 #include "build/build_config.h"
31 #include "build/debug.h"
33 #include "common/crc.h"
34 #include "common/maths.h"
35 #include "common/utils.h"
37 #include "config/config.h"
39 #include "pg/rx.h"
41 #include "drivers/persistent.h"
42 #include "drivers/serial.h"
43 #include "drivers/serial_uart.h"
44 #include "drivers/system.h"
45 #include "drivers/time.h"
47 #include "io/serial.h"
49 #include "rx/rx.h"
50 #include "rx/crsf.h"
52 #include "telemetry/crsf.h"
54 #define CRSF_TIME_NEEDED_PER_FRAME_US 1750 // a maximally sized 64byte payload will take ~1550us, round up to 1750.
55 #define CRSF_TIME_BETWEEN_FRAMES_US 6667 // At fastest, frames are sent by the transmitter every 6.667 milliseconds, 150 Hz
57 #define CRSF_DIGITAL_CHANNEL_MIN 172
58 #define CRSF_DIGITAL_CHANNEL_MAX 1811
60 #define CRSF_PAYLOAD_OFFSET offsetof(crsfFrameDef_t, type)
62 #define CRSF_LINK_STATUS_UPDATE_TIMEOUT_US 250000 // 250ms, 4 Hz mode 1 telemetry
64 #define CRSF_FRAME_ERROR_COUNT_THRESHOLD 3
66 STATIC_UNIT_TESTED bool crsfFrameDone = false;
67 STATIC_UNIT_TESTED crsfFrame_t crsfFrame;
68 STATIC_UNIT_TESTED crsfFrame_t crsfChannelDataFrame;
69 STATIC_UNIT_TESTED uint32_t crsfChannelData[CRSF_MAX_CHANNEL];
71 static serialPort_t *serialPort;
72 static timeUs_t crsfFrameStartAtUs = 0;
73 static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX];
74 static uint8_t telemetryBufLen = 0;
75 static float channelScale = CRSF_RC_CHANNEL_SCALE_LEGACY;
77 #ifdef USE_RX_LINK_UPLINK_POWER
78 #define CRSF_UPLINK_POWER_LEVEL_MW_ITEMS_COUNT 9
79 // Uplink power levels by uplinkTXPower expressed in mW (250 mW is from ver >=4.00, 50 mW in a future version and for ExpressLRS)
80 const uint16_t uplinkTXPowerStatesMw[CRSF_UPLINK_POWER_LEVEL_MW_ITEMS_COUNT] = {0, 10, 25, 100, 500, 1000, 2000, 250, 50};
81 #endif
84 * CRSF protocol
86 * CRSF protocol uses a single wire half duplex uart connection.
87 * The master sends one frame every 4ms and the slave replies between two frames from the master.
89 * 420000 baud
90 * not inverted
91 * 8 Bit
92 * 1 Stop bit
93 * Big endian
94 * 420000 bit/s = 46667 byte/s (including stop bit) = 21.43us per byte
95 * Max frame size is 64 bytes
96 * A 64 byte frame plus 1 sync byte can be transmitted in 1393 microseconds.
98 * CRSF_TIME_NEEDED_PER_FRAME_US is set conservatively at 1500 microseconds
100 * Every frame has the structure:
101 * <Device address><Frame length><Type><Payload><CRC>
103 * Device address: (uint8_t)
104 * Frame length: length in bytes including Type (uint8_t)
105 * Type: (uint8_t)
106 * CRC: (uint8_t)
110 struct crsfPayloadRcChannelsPacked_s {
111 // 176 bits of data (11 bits per channel * 16 channels) = 22 bytes.
112 unsigned int chan0 : 11;
113 unsigned int chan1 : 11;
114 unsigned int chan2 : 11;
115 unsigned int chan3 : 11;
116 unsigned int chan4 : 11;
117 unsigned int chan5 : 11;
118 unsigned int chan6 : 11;
119 unsigned int chan7 : 11;
120 unsigned int chan8 : 11;
121 unsigned int chan9 : 11;
122 unsigned int chan10 : 11;
123 unsigned int chan11 : 11;
124 unsigned int chan12 : 11;
125 unsigned int chan13 : 11;
126 unsigned int chan14 : 11;
127 unsigned int chan15 : 11;
128 } __attribute__ ((__packed__));
130 typedef struct crsfPayloadRcChannelsPacked_s crsfPayloadRcChannelsPacked_t;
133 * SUBSET RC FRAME 0x17
135 * The structure of 0x17 frame consists of 8-bit configuration data & variable length packed channel data.
137 * definition of the configuration byte
138 * bits 0-4: number of first channel packed
139 * bits 5-6: resolution configuration of the channel data (00 -> 10 bits, 01 -> 11 bits, 10 -> 12 bits, 11 -> 13 bits)
140 * bit 7: reserved
142 * data structure of the channel data
143 * - first channel packed with specified resolution
144 * - second channel packed with specified resolution
145 * - third channel packed with specified resolution
146 * ...
147 * - last channel packed with specified resolution
151 #if defined(USE_CRSF_LINK_STATISTICS)
153 * 0x14 Link statistics
154 * Payload:
156 * uint8_t Uplink RSSI Ant. 1 ( dBm * -1 )
157 * uint8_t Uplink RSSI Ant. 2 ( dBm * -1 )
158 * uint8_t Uplink Package success rate / Link quality ( % )
159 * int8_t Uplink SNR ( db )
160 * uint8_t Diversity active antenna ( enum ant. 1 = 0, ant. 2 )
161 * uint8_t RF Mode ( enum 4fps = 0 , 50fps, 150hz)
162 * uint8_t Uplink TX Power ( enum 0mW = 0, 10mW, 25 mW, 100 mW, 500 mW, 1000 mW, 2000mW, 250mW )
163 * uint8_t Downlink RSSI ( dBm * -1 )
164 * uint8_t Downlink package success rate / Link quality ( % )
165 * int8_t Downlink SNR ( db )
166 * Uplink is the connection from the ground to the UAV and downlink the opposite direction.
170 * 0x1C Link statistics RX
171 * Payload:
173 * uint8_t Downlink RSSI ( dBm * -1 )
174 * uint8_t Downlink RSSI ( % )
175 * uint8_t Downlink Package success rate / Link quality ( % )
176 * int8_t Downlink SNR ( db )
177 * uint8_t Uplink RF Power ( db )
181 * 0x1D Link statistics TX
182 * Payload:
184 * uint8_t Uplink RSSI ( dBm * -1 )
185 * uint8_t Uplink RSSI ( % )
186 * uint8_t Uplink Package success rate / Link quality ( % )
187 * int8_t Uplink SNR ( db )
188 * uint8_t Downlink RF Power ( db )
189 * uint8_t Uplink FPS ( FPS / 10 )
192 typedef struct crsfPayloadLinkstatistics_s {
193 uint8_t uplink_RSSI_1;
194 uint8_t uplink_RSSI_2;
195 uint8_t uplink_Link_quality;
196 int8_t uplink_SNR;
197 uint8_t active_antenna;
198 uint8_t rf_Mode;
199 uint8_t uplink_TX_Power;
200 uint8_t downlink_RSSI;
201 uint8_t downlink_Link_quality;
202 int8_t downlink_SNR;
203 } crsfLinkStatistics_t;
205 #if defined(USE_CRSF_V3)
206 typedef struct crsfPayloadLinkstatisticsRx_s {
207 uint8_t downlink_RSSI_1;
208 uint8_t downlink_RSSI_1_percentage;
209 uint8_t downlink_Link_quality;
210 int8_t downlink_SNR;
211 uint8_t uplink_power;
212 } crsfLinkStatisticsRx_t; // this struct is currently not used
214 typedef struct crsfPayloadLinkstatisticsTx_s {
215 uint8_t uplink_RSSI;
216 uint8_t uplink_RSSI_percentage;
217 uint8_t uplink_Link_quality;
218 int8_t uplink_SNR;
219 uint8_t downlink_power; // currently not used
220 uint8_t uplink_FPS; // currently not used
221 } crsfLinkStatisticsTx_t;
222 #endif
224 static timeUs_t lastLinkStatisticsFrameUs;
226 static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t* statsPtr, timeUs_t currentTimeUs)
228 const crsfLinkStatistics_t stats = *statsPtr;
229 lastLinkStatisticsFrameUs = currentTimeUs;
230 int16_t rssiDbm = -1 * (stats.active_antenna ? stats.uplink_RSSI_2 : stats.uplink_RSSI_1);
231 if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) {
232 if (rxConfig()->crsf_use_rx_snr) {
233 // -10dB of SNR mapped to 0 RSSI (fail safe is likely to happen at this measure)
234 // 0dB of SNR mapped to 20 RSSI (default alarm)
235 // 41dB of SNR mapped to 99 RSSI (SNR can climb to around 60, but showing that is not very meaningful)
236 const uint16_t rsnrPercentScaled = constrain((stats.uplink_SNR + 10) * 20, 0, RSSI_MAX_VALUE);
237 setRssi(rsnrPercentScaled, RSSI_SOURCE_RX_PROTOCOL_CRSF);
238 #ifdef USE_RX_RSSI_DBM
239 rssiDbm = stats.uplink_SNR;
240 #endif
241 } else {
242 const uint16_t rssiPercentScaled = scaleRange(rssiDbm, CRSF_RSSI_MIN, 0, 0, RSSI_MAX_VALUE);
243 setRssi(rssiPercentScaled, RSSI_SOURCE_RX_PROTOCOL_CRSF);
246 #ifdef USE_RX_RSSI_DBM
247 setRssiDbm(rssiDbm, RSSI_SOURCE_RX_PROTOCOL_CRSF);
248 #endif
250 #ifdef USE_RX_LINK_QUALITY_INFO
251 if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) {
252 setLinkQualityDirect(stats.uplink_Link_quality);
253 rxSetRfMode(stats.rf_Mode);
255 #endif
257 #ifdef USE_RX_LINK_UPLINK_POWER
258 const uint8_t crsfUplinkPowerStatesItemIndex = (stats.uplink_TX_Power < CRSF_UPLINK_POWER_LEVEL_MW_ITEMS_COUNT) ? stats.uplink_TX_Power : 0;
259 rxSetUplinkTxPwrMw(uplinkTXPowerStatesMw[crsfUplinkPowerStatesItemIndex]);
260 #endif
262 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 0, stats.uplink_RSSI_1);
263 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 1, stats.uplink_RSSI_2);
264 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 2, stats.uplink_Link_quality);
265 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 3, stats.rf_Mode);
267 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_PWR, 0, stats.active_antenna);
268 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_PWR, 1, stats.uplink_SNR);
269 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_PWR, 2, stats.uplink_TX_Power);
271 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_DOWN, 0, stats.downlink_RSSI);
272 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_DOWN, 1, stats.downlink_Link_quality);
273 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_DOWN, 2, stats.downlink_SNR);
276 #if defined(USE_CRSF_V3)
277 static void handleCrsfLinkStatisticsTxFrame(const crsfLinkStatisticsTx_t* statsPtr, timeUs_t currentTimeUs)
279 const crsfLinkStatisticsTx_t stats = *statsPtr;
280 lastLinkStatisticsFrameUs = currentTimeUs;
281 if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) {
282 const uint16_t rssiPercentScaled = scaleRange(stats.uplink_RSSI_percentage, 0, 100, 0, RSSI_MAX_VALUE);
283 setRssi(rssiPercentScaled, RSSI_SOURCE_RX_PROTOCOL_CRSF);
285 #ifdef USE_RX_RSSI_DBM
286 int16_t rssiDbm = -1 * stats.uplink_RSSI;
287 if (rxConfig()->crsf_use_rx_snr) {
288 rssiDbm = stats.uplink_SNR;
290 setRssiDbm(rssiDbm, RSSI_SOURCE_RX_PROTOCOL_CRSF);
291 #endif
293 #ifdef USE_RX_LINK_QUALITY_INFO
294 if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) {
295 setLinkQualityDirect(stats.uplink_Link_quality);
297 #endif
299 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 0, stats.uplink_RSSI);
300 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 1, stats.uplink_SNR);
301 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 2, stats.uplink_Link_quality);
302 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 3, stats.uplink_RSSI_percentage);
304 #endif
305 #endif
307 #if defined(USE_CRSF_LINK_STATISTICS)
308 static void crsfCheckRssi(uint32_t currentTimeUs)
311 if (cmpTimeUs(currentTimeUs, lastLinkStatisticsFrameUs) > CRSF_LINK_STATUS_UPDATE_TIMEOUT_US) {
312 if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) {
313 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL_CRSF);
314 #ifdef USE_RX_RSSI_DBM
315 if (rxConfig()->crsf_use_rx_snr) {
316 setRssiDbmDirect(CRSF_SNR_MIN, RSSI_SOURCE_RX_PROTOCOL_CRSF);
317 } else {
318 setRssiDbmDirect(CRSF_RSSI_MIN, RSSI_SOURCE_RX_PROTOCOL_CRSF);
320 #endif
322 #ifdef USE_RX_LINK_QUALITY_INFO
323 if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) {
324 setLinkQualityDirect(0);
326 #endif
329 #endif
331 STATIC_UNIT_TESTED uint8_t crsfFrameCRC(void)
333 // CRC includes type and payload
334 uint8_t crc = crc8_dvb_s2(0, crsfFrame.frame.type);
335 for (int ii = 0; ii < crsfFrame.frame.frameLength - CRSF_FRAME_LENGTH_TYPE_CRC; ++ii) {
336 crc = crc8_dvb_s2(crc, crsfFrame.frame.payload[ii]);
338 return crc;
341 STATIC_UNIT_TESTED uint8_t crsfFrameCmdCRC(void)
343 // CRC includes type and payload
344 uint8_t crc = crc8_poly_0xba(0, crsfFrame.frame.type);
345 for (int ii = 0; ii < crsfFrame.frame.frameLength - CRSF_FRAME_LENGTH_TYPE_CRC - 1; ++ii) {
346 crc = crc8_poly_0xba(crc, crsfFrame.frame.payload[ii]);
348 return crc;
351 // Receive ISR callback, called back from serial port
352 STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
354 rxRuntimeState_t *const rxRuntimeState = (rxRuntimeState_t *const)data;
356 static uint8_t crsfFramePosition = 0;
357 #if defined(USE_CRSF_V3)
358 static uint8_t crsfFrameErrorCnt = 0;
359 #endif
360 const timeUs_t currentTimeUs = microsISR();
362 #ifdef DEBUG_CRSF_PACKETS
363 debug[2] = currentTimeUs - crsfFrameStartAtUs;
364 #endif
366 if (cmpTimeUs(currentTimeUs, crsfFrameStartAtUs) > CRSF_TIME_NEEDED_PER_FRAME_US) {
367 // We've received a character after max time needed to complete a frame,
368 // so this must be the start of a new frame.
369 #if defined(USE_CRSF_V3)
370 if (crsfFramePosition > 0) {
371 // count an error if full valid frame not received within the allowed time.
372 crsfFrameErrorCnt++;
374 #endif
375 crsfFramePosition = 0;
378 if (crsfFramePosition == 0) {
379 crsfFrameStartAtUs = currentTimeUs;
381 // assume frame is 5 bytes long until we have received the frame length
382 // full frame length includes the length of the address and framelength fields
383 // sometimes we can receive some garbage data. So, we need to check max size for preventing buffer overrun.
384 const int fullFrameLength = crsfFramePosition < 3 ? 5 : MIN(crsfFrame.frame.frameLength + CRSF_FRAME_LENGTH_ADDRESS + CRSF_FRAME_LENGTH_FRAMELENGTH, CRSF_FRAME_SIZE_MAX);
386 if (crsfFramePosition < fullFrameLength) {
387 crsfFrame.bytes[crsfFramePosition++] = (uint8_t)c;
388 if (crsfFramePosition >= fullFrameLength) {
389 crsfFramePosition = 0;
390 const uint8_t crc = crsfFrameCRC();
391 if (crc == crsfFrame.bytes[fullFrameLength - 1]) {
392 #if defined(USE_CRSF_V3)
393 crsfFrameErrorCnt = 0;
394 #endif
395 switch (crsfFrame.frame.type) {
396 case CRSF_FRAMETYPE_RC_CHANNELS_PACKED:
397 case CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED:
398 if (crsfFrame.frame.deviceAddress == CRSF_ADDRESS_FLIGHT_CONTROLLER) {
399 rxRuntimeState->lastRcFrameTimeUs = currentTimeUs;
400 crsfFrameDone = true;
401 memcpy(&crsfChannelDataFrame, &crsfFrame, sizeof(crsfFrame));
403 break;
405 #if defined(USE_TELEMETRY_CRSF) && defined(USE_MSP_OVER_TELEMETRY)
406 case CRSF_FRAMETYPE_MSP_REQ:
407 case CRSF_FRAMETYPE_MSP_WRITE: {
408 uint8_t *frameStart = (uint8_t *)&crsfFrame.frame.payload + CRSF_FRAME_ORIGIN_DEST_SIZE;
409 if (bufferCrsfMspFrame(frameStart, crsfFrame.frame.frameLength - 4)) {
410 crsfScheduleMspResponse(crsfFrame.frame.payload[1]);
412 break;
414 #endif
415 #if defined(USE_CRSF_CMS_TELEMETRY)
416 case CRSF_FRAMETYPE_DEVICE_PING:
417 crsfScheduleDeviceInfoResponse();
418 break;
419 case CRSF_FRAMETYPE_DISPLAYPORT_CMD: {
420 uint8_t *frameStart = (uint8_t *)&crsfFrame.frame.payload + CRSF_FRAME_ORIGIN_DEST_SIZE;
421 crsfProcessDisplayPortCmd(frameStart);
422 break;
424 #endif
425 #if defined(USE_CRSF_LINK_STATISTICS)
427 case CRSF_FRAMETYPE_LINK_STATISTICS: {
428 // if to FC and 10 bytes + CRSF_FRAME_ORIGIN_DEST_SIZE
429 if ((rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) &&
430 (crsfFrame.frame.deviceAddress == CRSF_ADDRESS_FLIGHT_CONTROLLER) &&
431 (crsfFrame.frame.frameLength == CRSF_FRAME_ORIGIN_DEST_SIZE + CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE)) {
432 const crsfLinkStatistics_t* statsFrame = (const crsfLinkStatistics_t*)&crsfFrame.frame.payload;
433 handleCrsfLinkStatisticsFrame(statsFrame, currentTimeUs);
435 break;
437 #if defined(USE_CRSF_V3)
438 case CRSF_FRAMETYPE_LINK_STATISTICS_RX: {
439 break;
441 case CRSF_FRAMETYPE_LINK_STATISTICS_TX: {
442 if ((rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) &&
443 (crsfFrame.frame.deviceAddress == CRSF_ADDRESS_FLIGHT_CONTROLLER) &&
444 (crsfFrame.frame.frameLength == CRSF_FRAME_ORIGIN_DEST_SIZE + CRSF_FRAME_LINK_STATISTICS_TX_PAYLOAD_SIZE)) {
445 const crsfLinkStatisticsTx_t* statsFrame = (const crsfLinkStatisticsTx_t*)&crsfFrame.frame.payload;
446 handleCrsfLinkStatisticsTxFrame(statsFrame, currentTimeUs);
448 break;
450 #endif
451 #endif
452 #if defined(USE_CRSF_V3)
453 case CRSF_FRAMETYPE_COMMAND:
454 if ((crsfFrame.bytes[fullFrameLength - 2] == crsfFrameCmdCRC()) &&
455 (crsfFrame.bytes[3] == CRSF_ADDRESS_FLIGHT_CONTROLLER)) {
456 crsfProcessCommand(crsfFrame.frame.payload + CRSF_FRAME_ORIGIN_DEST_SIZE);
458 break;
459 #endif
460 default:
461 break;
463 } else {
464 #if defined(USE_CRSF_V3)
465 if (crsfFrameErrorCnt < CRSF_FRAME_ERROR_COUNT_THRESHOLD)
466 crsfFrameErrorCnt++;
467 #endif
470 #if defined(USE_CRSF_V3)
471 if (crsfBaudNegotiationInProgress() || isEepromWriteInProgress()) {
472 // don't count errors when negotiation or eeprom write is in progress
473 crsfFrameErrorCnt = 0;
474 } else if (crsfFrameErrorCnt >= CRSF_FRAME_ERROR_COUNT_THRESHOLD) {
475 // fall back to default speed if speed mismatch detected
476 setCrsfDefaultSpeed();
477 crsfFrameErrorCnt = 0;
479 #endif
483 STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeState_t *rxRuntimeState)
485 UNUSED(rxRuntimeState);
487 #if defined(USE_CRSF_LINK_STATISTICS)
488 crsfCheckRssi(micros());
489 #endif
490 if (crsfFrameDone) {
491 crsfFrameDone = false;
493 // unpack the RC channels
494 if (crsfChannelDataFrame.frame.type == CRSF_FRAMETYPE_RC_CHANNELS_PACKED) {
495 // use ordinary RC frame structure (0x16)
496 const crsfPayloadRcChannelsPacked_t* const rcChannels = (crsfPayloadRcChannelsPacked_t*)&crsfChannelDataFrame.frame.payload;
497 channelScale = CRSF_RC_CHANNEL_SCALE_LEGACY;
498 crsfChannelData[0] = rcChannels->chan0;
499 crsfChannelData[1] = rcChannels->chan1;
500 crsfChannelData[2] = rcChannels->chan2;
501 crsfChannelData[3] = rcChannels->chan3;
502 crsfChannelData[4] = rcChannels->chan4;
503 crsfChannelData[5] = rcChannels->chan5;
504 crsfChannelData[6] = rcChannels->chan6;
505 crsfChannelData[7] = rcChannels->chan7;
506 crsfChannelData[8] = rcChannels->chan8;
507 crsfChannelData[9] = rcChannels->chan9;
508 crsfChannelData[10] = rcChannels->chan10;
509 crsfChannelData[11] = rcChannels->chan11;
510 crsfChannelData[12] = rcChannels->chan12;
511 crsfChannelData[13] = rcChannels->chan13;
512 crsfChannelData[14] = rcChannels->chan14;
513 crsfChannelData[15] = rcChannels->chan15;
514 } else {
515 // use subset RC frame structure (0x17)
516 uint8_t readByteIndex = 0;
517 const uint8_t *payload = crsfChannelDataFrame.frame.payload;
519 // get the configuration byte
520 uint8_t configByte = payload[readByteIndex++];
522 // get the channel number of start channel
523 uint8_t startChannel = configByte & CRSF_SUBSET_RC_STARTING_CHANNEL_MASK;
524 configByte >>= CRSF_SUBSET_RC_STARTING_CHANNEL_BITS;
526 // get the channel resolution settings
527 uint8_t channelBits;
528 uint16_t channelMask;
529 uint8_t channelRes = configByte & CRSF_SUBSET_RC_RES_CONFIGURATION_MASK;
530 configByte >>= CRSF_SUBSET_RC_RES_CONFIGURATION_BITS;
531 switch (channelRes) {
532 case CRSF_SUBSET_RC_RES_CONF_10B:
533 channelBits = CRSF_SUBSET_RC_RES_BITS_10B;
534 channelMask = CRSF_SUBSET_RC_RES_MASK_10B;
535 channelScale = CRSF_SUBSET_RC_CHANNEL_SCALE_10B;
536 break;
537 default:
538 case CRSF_SUBSET_RC_RES_CONF_11B:
539 channelBits = CRSF_SUBSET_RC_RES_BITS_11B;
540 channelMask = CRSF_SUBSET_RC_RES_MASK_11B;
541 channelScale = CRSF_SUBSET_RC_CHANNEL_SCALE_11B;
542 break;
543 case CRSF_SUBSET_RC_RES_CONF_12B:
544 channelBits = CRSF_SUBSET_RC_RES_BITS_12B;
545 channelMask = CRSF_SUBSET_RC_RES_MASK_12B;
546 channelScale = CRSF_SUBSET_RC_CHANNEL_SCALE_12B;
547 break;
548 case CRSF_SUBSET_RC_RES_CONF_13B:
549 channelBits = CRSF_SUBSET_RC_RES_BITS_13B;
550 channelMask = CRSF_SUBSET_RC_RES_MASK_13B;
551 channelScale = CRSF_SUBSET_RC_CHANNEL_SCALE_13B;
552 break;
555 // do nothing for the reserved configuration bit
556 configByte >>= CRSF_SUBSET_RC_RESERVED_CONFIGURATION_BITS;
558 // calculate the number of channels packed
559 uint8_t numOfChannels = ((crsfChannelDataFrame.frame.frameLength - CRSF_FRAME_LENGTH_TYPE_CRC - 1) * 8) / channelBits;
561 // unpack the channel data
562 uint8_t bitsMerged = 0;
563 uint32_t readValue = 0;
564 for (uint8_t n = 0; n < numOfChannels; n++) {
565 while (bitsMerged < channelBits) {
566 uint8_t readByte = payload[readByteIndex++];
567 readValue |= ((uint32_t) readByte) << bitsMerged;
568 bitsMerged += 8;
570 crsfChannelData[startChannel + n] = readValue & channelMask;
571 readValue >>= channelBits;
572 bitsMerged -= channelBits;
575 return RX_FRAME_COMPLETE;
577 return RX_FRAME_PENDING;
580 STATIC_UNIT_TESTED float crsfReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
582 UNUSED(rxRuntimeState);
583 if (channelScale == CRSF_RC_CHANNEL_SCALE_LEGACY) {
584 /* conversion from RC value to PWM
585 * for 0x16 RC frame
586 * RC PWM
587 * min 172 -> 988us
588 * mid 992 -> 1500us
589 * max 1811 -> 2012us
590 * scale factor = (2012-988) / (1811-172) = 0.62477120195241
591 * offset = 988 - 172 * 0.62477120195241 = 880.53935326418548
593 return (channelScale * (float)crsfChannelData[chan]) + 881;
594 } else {
595 /* conversion from RC value to PWM
596 * for 0x17 Subset RC frame
598 return (channelScale * (float)crsfChannelData[chan]) + 988;
602 void crsfRxWriteTelemetryData(const void *data, int len)
604 len = MIN(len, (int)sizeof(telemetryBuf));
605 memcpy(telemetryBuf, data, len);
606 telemetryBufLen = len;
609 void crsfRxSendTelemetryData(void)
611 // if there is telemetry data to write
612 if (telemetryBufLen > 0) {
613 serialWriteBuf(serialPort, telemetryBuf, telemetryBufLen);
614 telemetryBufLen = 0; // reset telemetry buffer
618 bool crsfRxIsTelemetryBufEmpty(void)
620 return telemetryBufLen == 0;
623 bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
625 for (int ii = 0; ii < CRSF_MAX_CHANNEL; ++ii) {
626 crsfChannelData[ii] = (16 * rxConfig->midrc) / 10 - 1408;
629 rxRuntimeState->channelCount = CRSF_MAX_CHANNEL;
630 rxRuntimeState->rcReadRawFn = crsfReadRawRC;
631 rxRuntimeState->rcFrameStatusFn = crsfFrameStatus;
632 rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
634 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
635 if (!portConfig) {
636 return false;
639 uint32_t crsfBaudrate = CRSF_BAUDRATE;
641 #if defined(USE_CRSF_V3)
642 crsfBaudrate = rxConfig->crsf_use_negotiated_baud ? getCrsfCachedBaudrate() : CRSF_BAUDRATE;
643 #endif
645 serialPort = openSerialPort(portConfig->identifier,
646 FUNCTION_RX_SERIAL,
647 crsfDataReceive,
648 rxRuntimeState,
649 crsfBaudrate,
650 CRSF_PORT_MODE,
651 CRSF_PORT_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0)
654 if (rssiSource == RSSI_SOURCE_NONE) {
655 rssiSource = RSSI_SOURCE_RX_PROTOCOL_CRSF;
657 #ifdef USE_RX_LINK_QUALITY_INFO
658 if (linkQualitySource == LQ_SOURCE_NONE) {
659 linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
661 #endif
663 return serialPort != NULL;
666 #if defined(USE_CRSF_V3)
667 void crsfRxUpdateBaudrate(uint32_t baudrate)
669 serialSetBaudRate(serialPort, baudrate);
670 persistentObjectWrite(PERSISTENT_OBJECT_SERIALRX_BAUD, baudrate);
673 bool crsfRxUseNegotiatedBaud(void)
675 return rxConfig()->crsf_use_negotiated_baud;
677 #endif
679 bool crsfRxIsActive(void)
681 return serialPort != NULL;
683 #endif