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/>.
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"
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"
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};
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.
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)
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)
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
147 * - last channel packed with specified resolution
151 #if defined(USE_CRSF_LINK_STATISTICS)
153 * 0x14 Link statistics
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
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
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
;
197 uint8_t active_antenna
;
199 uint8_t uplink_TX_Power
;
200 uint8_t downlink_RSSI
;
201 uint8_t downlink_Link_quality
;
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
;
211 uint8_t uplink_power
;
212 } crsfLinkStatisticsRx_t
; // this struct is currently not used
214 typedef struct crsfPayloadLinkstatisticsTx_s
{
216 uint8_t uplink_RSSI_percentage
;
217 uint8_t uplink_Link_quality
;
219 uint8_t downlink_power
; // currently not used
220 uint8_t uplink_FPS
; // currently not used
221 } crsfLinkStatisticsTx_t
;
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
;
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
);
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
);
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
]);
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
);
293 #ifdef USE_RX_LINK_QUALITY_INFO
294 if (linkQualitySource
== LQ_SOURCE_RX_PROTOCOL_CRSF
) {
295 setLinkQualityDirect(stats
.uplink_Link_quality
);
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
);
307 #if defined(USE_CRSF_LINK_STATISTICS)
308 static void crsfCheckRssi(uint32_t currentTimeUs
) {
310 if (cmpTimeUs(currentTimeUs
, lastLinkStatisticsFrameUs
) > CRSF_LINK_STATUS_UPDATE_TIMEOUT_US
) {
311 if (rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) {
312 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
313 #ifdef USE_RX_RSSI_DBM
314 if (rxConfig()->crsf_use_rx_snr
) {
315 setRssiDbmDirect(CRSF_SNR_MIN
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
317 setRssiDbmDirect(CRSF_RSSI_MIN
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
321 #ifdef USE_RX_LINK_QUALITY_INFO
322 if (linkQualitySource
== LQ_SOURCE_RX_PROTOCOL_CRSF
) {
323 setLinkQualityDirect(0);
330 STATIC_UNIT_TESTED
uint8_t crsfFrameCRC(void)
332 // CRC includes type and payload
333 uint8_t crc
= crc8_dvb_s2(0, crsfFrame
.frame
.type
);
334 for (int ii
= 0; ii
< crsfFrame
.frame
.frameLength
- CRSF_FRAME_LENGTH_TYPE_CRC
; ++ii
) {
335 crc
= crc8_dvb_s2(crc
, crsfFrame
.frame
.payload
[ii
]);
340 STATIC_UNIT_TESTED
uint8_t crsfFrameCmdCRC(void)
342 // CRC includes type and payload
343 uint8_t crc
= crc8_poly_0xba(0, crsfFrame
.frame
.type
);
344 for (int ii
= 0; ii
< crsfFrame
.frame
.frameLength
- CRSF_FRAME_LENGTH_TYPE_CRC
- 1; ++ii
) {
345 crc
= crc8_poly_0xba(crc
, crsfFrame
.frame
.payload
[ii
]);
350 // Receive ISR callback, called back from serial port
351 STATIC_UNIT_TESTED
void crsfDataReceive(uint16_t c
, void *data
)
353 rxRuntimeState_t
*const rxRuntimeState
= (rxRuntimeState_t
*const)data
;
355 static uint8_t crsfFramePosition
= 0;
356 #if defined(USE_CRSF_V3)
357 static uint8_t crsfFrameErrorCnt
= 0;
359 const timeUs_t currentTimeUs
= microsISR();
361 #ifdef DEBUG_CRSF_PACKETS
362 debug
[2] = currentTimeUs
- crsfFrameStartAtUs
;
365 if (cmpTimeUs(currentTimeUs
, crsfFrameStartAtUs
) > CRSF_TIME_NEEDED_PER_FRAME_US
) {
366 // We've received a character after max time needed to complete a frame,
367 // so this must be the start of a new frame.
368 #if defined(USE_CRSF_V3)
369 if (crsfFramePosition
> 0) {
370 // count an error if full valid frame not received within the allowed time.
374 crsfFramePosition
= 0;
377 if (crsfFramePosition
== 0) {
378 crsfFrameStartAtUs
= currentTimeUs
;
380 // assume frame is 5 bytes long until we have received the frame length
381 // full frame length includes the length of the address and framelength fields
382 // sometimes we can receive some garbage data. So, we need to check max size for preventing buffer overrun.
383 const int fullFrameLength
= crsfFramePosition
< 3 ? 5 : MIN(crsfFrame
.frame
.frameLength
+ CRSF_FRAME_LENGTH_ADDRESS
+ CRSF_FRAME_LENGTH_FRAMELENGTH
, CRSF_FRAME_SIZE_MAX
);
385 if (crsfFramePosition
< fullFrameLength
) {
386 crsfFrame
.bytes
[crsfFramePosition
++] = (uint8_t)c
;
387 if (crsfFramePosition
>= fullFrameLength
) {
388 crsfFramePosition
= 0;
389 const uint8_t crc
= crsfFrameCRC();
390 if (crc
== crsfFrame
.bytes
[fullFrameLength
- 1]) {
391 #if defined(USE_CRSF_V3)
392 crsfFrameErrorCnt
= 0;
394 switch (crsfFrame
.frame
.type
) {
395 case CRSF_FRAMETYPE_RC_CHANNELS_PACKED
:
396 case CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED
:
397 if (crsfFrame
.frame
.deviceAddress
== CRSF_ADDRESS_FLIGHT_CONTROLLER
) {
398 rxRuntimeState
->lastRcFrameTimeUs
= currentTimeUs
;
399 crsfFrameDone
= true;
400 memcpy(&crsfChannelDataFrame
, &crsfFrame
, sizeof(crsfFrame
));
404 #if defined(USE_TELEMETRY_CRSF) && defined(USE_MSP_OVER_TELEMETRY)
405 case CRSF_FRAMETYPE_MSP_REQ
:
406 case CRSF_FRAMETYPE_MSP_WRITE
: {
407 uint8_t *frameStart
= (uint8_t *)&crsfFrame
.frame
.payload
+ CRSF_FRAME_ORIGIN_DEST_SIZE
;
408 if (bufferCrsfMspFrame(frameStart
, crsfFrame
.frame
.frameLength
- 4)) {
409 crsfScheduleMspResponse(crsfFrame
.frame
.payload
[1]);
414 #if defined(USE_CRSF_CMS_TELEMETRY)
415 case CRSF_FRAMETYPE_DEVICE_PING
:
416 crsfScheduleDeviceInfoResponse();
418 case CRSF_FRAMETYPE_DISPLAYPORT_CMD
: {
419 uint8_t *frameStart
= (uint8_t *)&crsfFrame
.frame
.payload
+ CRSF_FRAME_ORIGIN_DEST_SIZE
;
420 crsfProcessDisplayPortCmd(frameStart
);
424 #if defined(USE_CRSF_LINK_STATISTICS)
426 case CRSF_FRAMETYPE_LINK_STATISTICS
: {
427 // if to FC and 10 bytes + CRSF_FRAME_ORIGIN_DEST_SIZE
428 if ((rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) &&
429 (crsfFrame
.frame
.deviceAddress
== CRSF_ADDRESS_FLIGHT_CONTROLLER
) &&
430 (crsfFrame
.frame
.frameLength
== CRSF_FRAME_ORIGIN_DEST_SIZE
+ CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE
)) {
431 const crsfLinkStatistics_t
* statsFrame
= (const crsfLinkStatistics_t
*)&crsfFrame
.frame
.payload
;
432 handleCrsfLinkStatisticsFrame(statsFrame
, currentTimeUs
);
436 #if defined(USE_CRSF_V3)
437 case CRSF_FRAMETYPE_LINK_STATISTICS_RX
: {
440 case CRSF_FRAMETYPE_LINK_STATISTICS_TX
: {
441 if ((rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) &&
442 (crsfFrame
.frame
.deviceAddress
== CRSF_ADDRESS_FLIGHT_CONTROLLER
) &&
443 (crsfFrame
.frame
.frameLength
== CRSF_FRAME_ORIGIN_DEST_SIZE
+ CRSF_FRAME_LINK_STATISTICS_TX_PAYLOAD_SIZE
)) {
444 const crsfLinkStatisticsTx_t
* statsFrame
= (const crsfLinkStatisticsTx_t
*)&crsfFrame
.frame
.payload
;
445 handleCrsfLinkStatisticsTxFrame(statsFrame
, currentTimeUs
);
451 #if defined(USE_CRSF_V3)
452 case CRSF_FRAMETYPE_COMMAND
:
453 if ((crsfFrame
.bytes
[fullFrameLength
- 2] == crsfFrameCmdCRC()) &&
454 (crsfFrame
.bytes
[3] == CRSF_ADDRESS_FLIGHT_CONTROLLER
)) {
455 crsfProcessCommand(crsfFrame
.frame
.payload
+ CRSF_FRAME_ORIGIN_DEST_SIZE
);
463 #if defined(USE_CRSF_V3)
464 if (crsfFrameErrorCnt
< CRSF_FRAME_ERROR_COUNT_THRESHOLD
)
469 #if defined(USE_CRSF_V3)
470 if (crsfBaudNegotiationInProgress() || isEepromWriteInProgress()) {
471 // don't count errors when negotiation or eeprom write is in progress
472 crsfFrameErrorCnt
= 0;
473 } else if (crsfFrameErrorCnt
>= CRSF_FRAME_ERROR_COUNT_THRESHOLD
) {
474 // fall back to default speed if speed mismatch detected
475 setCrsfDefaultSpeed();
476 crsfFrameErrorCnt
= 0;
482 STATIC_UNIT_TESTED
uint8_t crsfFrameStatus(rxRuntimeState_t
*rxRuntimeState
)
484 UNUSED(rxRuntimeState
);
486 #if defined(USE_CRSF_LINK_STATISTICS)
487 crsfCheckRssi(micros());
490 crsfFrameDone
= false;
492 // unpack the RC channels
493 if (crsfChannelDataFrame
.frame
.type
== CRSF_FRAMETYPE_RC_CHANNELS_PACKED
) {
494 // use ordinary RC frame structure (0x16)
495 const crsfPayloadRcChannelsPacked_t
* const rcChannels
= (crsfPayloadRcChannelsPacked_t
*)&crsfChannelDataFrame
.frame
.payload
;
496 channelScale
= CRSF_RC_CHANNEL_SCALE_LEGACY
;
497 crsfChannelData
[0] = rcChannels
->chan0
;
498 crsfChannelData
[1] = rcChannels
->chan1
;
499 crsfChannelData
[2] = rcChannels
->chan2
;
500 crsfChannelData
[3] = rcChannels
->chan3
;
501 crsfChannelData
[4] = rcChannels
->chan4
;
502 crsfChannelData
[5] = rcChannels
->chan5
;
503 crsfChannelData
[6] = rcChannels
->chan6
;
504 crsfChannelData
[7] = rcChannels
->chan7
;
505 crsfChannelData
[8] = rcChannels
->chan8
;
506 crsfChannelData
[9] = rcChannels
->chan9
;
507 crsfChannelData
[10] = rcChannels
->chan10
;
508 crsfChannelData
[11] = rcChannels
->chan11
;
509 crsfChannelData
[12] = rcChannels
->chan12
;
510 crsfChannelData
[13] = rcChannels
->chan13
;
511 crsfChannelData
[14] = rcChannels
->chan14
;
512 crsfChannelData
[15] = rcChannels
->chan15
;
514 // use subset RC frame structure (0x17)
515 uint8_t readByteIndex
= 0;
516 const uint8_t *payload
= crsfChannelDataFrame
.frame
.payload
;
518 // get the configuration byte
519 uint8_t configByte
= payload
[readByteIndex
++];
521 // get the channel number of start channel
522 uint8_t startChannel
= configByte
& CRSF_SUBSET_RC_STARTING_CHANNEL_MASK
;
523 configByte
>>= CRSF_SUBSET_RC_STARTING_CHANNEL_BITS
;
525 // get the channel resolution settings
527 uint16_t channelMask
;
528 uint8_t channelRes
= configByte
& CRSF_SUBSET_RC_RES_CONFIGURATION_MASK
;
529 configByte
>>= CRSF_SUBSET_RC_RES_CONFIGURATION_BITS
;
530 switch (channelRes
) {
531 case CRSF_SUBSET_RC_RES_CONF_10B
:
532 channelBits
= CRSF_SUBSET_RC_RES_BITS_10B
;
533 channelMask
= CRSF_SUBSET_RC_RES_MASK_10B
;
534 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_10B
;
537 case CRSF_SUBSET_RC_RES_CONF_11B
:
538 channelBits
= CRSF_SUBSET_RC_RES_BITS_11B
;
539 channelMask
= CRSF_SUBSET_RC_RES_MASK_11B
;
540 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_11B
;
542 case CRSF_SUBSET_RC_RES_CONF_12B
:
543 channelBits
= CRSF_SUBSET_RC_RES_BITS_12B
;
544 channelMask
= CRSF_SUBSET_RC_RES_MASK_12B
;
545 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_12B
;
547 case CRSF_SUBSET_RC_RES_CONF_13B
:
548 channelBits
= CRSF_SUBSET_RC_RES_BITS_13B
;
549 channelMask
= CRSF_SUBSET_RC_RES_MASK_13B
;
550 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_13B
;
554 // do nothing for the reserved configuration bit
555 configByte
>>= CRSF_SUBSET_RC_RESERVED_CONFIGURATION_BITS
;
557 // calculate the number of channels packed
558 uint8_t numOfChannels
= ((crsfChannelDataFrame
.frame
.frameLength
- CRSF_FRAME_LENGTH_TYPE_CRC
- 1) * 8) / channelBits
;
560 // unpack the channel data
561 uint8_t bitsMerged
= 0;
562 uint32_t readValue
= 0;
563 for (uint8_t n
= 0; n
< numOfChannels
; n
++) {
564 while (bitsMerged
< channelBits
) {
565 uint8_t readByte
= payload
[readByteIndex
++];
566 readValue
|= ((uint32_t) readByte
) << bitsMerged
;
569 crsfChannelData
[startChannel
+ n
] = readValue
& channelMask
;
570 readValue
>>= channelBits
;
571 bitsMerged
-= channelBits
;
574 return RX_FRAME_COMPLETE
;
576 return RX_FRAME_PENDING
;
579 STATIC_UNIT_TESTED
float crsfReadRawRC(const rxRuntimeState_t
*rxRuntimeState
, uint8_t chan
)
581 UNUSED(rxRuntimeState
);
582 if (channelScale
== CRSF_RC_CHANNEL_SCALE_LEGACY
) {
583 /* conversion from RC value to PWM
589 * scale factor = (2012-988) / (1811-172) = 0.62477120195241
590 * offset = 988 - 172 * 0.62477120195241 = 880.53935326418548
592 return (channelScale
* (float)crsfChannelData
[chan
]) + 881;
594 /* conversion from RC value to PWM
595 * for 0x17 Subset RC frame
597 return (channelScale
* (float)crsfChannelData
[chan
]) + 988;
601 void crsfRxWriteTelemetryData(const void *data
, int len
)
603 len
= MIN(len
, (int)sizeof(telemetryBuf
));
604 memcpy(telemetryBuf
, data
, len
);
605 telemetryBufLen
= len
;
608 void crsfRxSendTelemetryData(void)
610 // if there is telemetry data to write
611 if (telemetryBufLen
> 0) {
612 serialWriteBuf(serialPort
, telemetryBuf
, telemetryBufLen
);
613 telemetryBufLen
= 0; // reset telemetry buffer
617 bool crsfRxIsTelemetryBufEmpty(void)
619 return telemetryBufLen
== 0;
622 bool crsfRxInit(const rxConfig_t
*rxConfig
, rxRuntimeState_t
*rxRuntimeState
)
624 for (int ii
= 0; ii
< CRSF_MAX_CHANNEL
; ++ii
) {
625 crsfChannelData
[ii
] = (16 * rxConfig
->midrc
) / 10 - 1408;
628 rxRuntimeState
->channelCount
= CRSF_MAX_CHANNEL
;
629 rxRuntimeState
->rcReadRawFn
= crsfReadRawRC
;
630 rxRuntimeState
->rcFrameStatusFn
= crsfFrameStatus
;
631 rxRuntimeState
->rcFrameTimeUsFn
= rxFrameTimeUs
;
633 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
638 uint32_t crsfBaudrate
= CRSF_BAUDRATE
;
640 #if defined(USE_CRSF_V3)
641 crsfBaudrate
= rxConfig
->crsf_use_negotiated_baud
? getCrsfCachedBaudrate() : CRSF_BAUDRATE
;
644 serialPort
= openSerialPort(portConfig
->identifier
,
650 CRSF_PORT_OPTIONS
| (rxConfig
->serialrx_inverted
? SERIAL_INVERTED
: 0)
653 if (rssiSource
== RSSI_SOURCE_NONE
) {
654 rssiSource
= RSSI_SOURCE_RX_PROTOCOL_CRSF
;
656 #ifdef USE_RX_LINK_QUALITY_INFO
657 if (linkQualitySource
== LQ_SOURCE_NONE
) {
658 linkQualitySource
= LQ_SOURCE_RX_PROTOCOL_CRSF
;
662 return serialPort
!= NULL
;
665 #if defined(USE_CRSF_V3)
666 void crsfRxUpdateBaudrate(uint32_t baudrate
)
668 serialSetBaudRate(serialPort
, baudrate
);
669 persistentObjectWrite(PERSISTENT_OBJECT_SERIALRX_BAUD
, baudrate
);
672 bool crsfRxUseNegotiatedBaud(void)
674 return rxConfig()->crsf_use_negotiated_baud
;
678 bool crsfRxIsActive(void)
680 return serialPort
!= NULL
;