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"
39 #include "drivers/serial.h"
40 #include "drivers/serial_uart.h"
41 #include "drivers/system.h"
42 #include "drivers/time.h"
44 #include "io/serial.h"
49 #include "telemetry/crsf.h"
51 #define CRSF_TIME_NEEDED_PER_FRAME_US 1100 // 700 ms + 400 ms for potential ad-hoc request
52 #define CRSF_TIME_BETWEEN_FRAMES_US 6667 // At fastest, frames are sent by the transmitter every 6.667 milliseconds, 150 Hz
54 #define CRSF_DIGITAL_CHANNEL_MIN 172
55 #define CRSF_DIGITAL_CHANNEL_MAX 1811
57 #define CRSF_PAYLOAD_OFFSET offsetof(crsfFrameDef_t, type)
59 #define CRSF_LINK_STATUS_UPDATE_TIMEOUT_US 250000 // 250ms, 4 Hz mode 1 telemetry
61 #define CRSF_FRAME_ERROR_COUNT_THRESHOLD 100
63 STATIC_UNIT_TESTED
bool crsfFrameDone
= false;
64 STATIC_UNIT_TESTED crsfFrame_t crsfFrame
;
65 STATIC_UNIT_TESTED crsfFrame_t crsfChannelDataFrame
;
66 STATIC_UNIT_TESTED
uint32_t crsfChannelData
[CRSF_MAX_CHANNEL
];
68 static serialPort_t
*serialPort
;
69 static timeUs_t crsfFrameStartAtUs
= 0;
70 static uint8_t telemetryBuf
[CRSF_FRAME_SIZE_MAX
];
71 static uint8_t telemetryBufLen
= 0;
72 static float channelScale
= CRSF_RC_CHANNEL_SCALE_LEGACY
;
74 #ifdef USE_RX_LINK_UPLINK_POWER
75 #define CRSF_UPLINK_POWER_LEVEL_MW_ITEMS_COUNT 9
76 // Uplink power levels by uplinkTXPower expressed in mW (250 mW is from ver >=4.00, 50 mW in a future version and for ExpressLRS)
77 const uint16_t uplinkTXPowerStatesMw
[CRSF_UPLINK_POWER_LEVEL_MW_ITEMS_COUNT
] = {0, 10, 25, 100, 500, 1000, 2000, 250, 50};
83 * CRSF protocol uses a single wire half duplex uart connection.
84 * The master sends one frame every 4ms and the slave replies between two frames from the master.
91 * 420000 bit/s = 46667 byte/s (including stop bit) = 21.43us per byte
92 * Max frame size is 64 bytes
93 * A 64 byte frame plus 1 sync byte can be transmitted in 1393 microseconds.
95 * CRSF_TIME_NEEDED_PER_FRAME_US is set conservatively at 1500 microseconds
97 * Every frame has the structure:
98 * <Device address><Frame length><Type><Payload><CRC>
100 * Device address: (uint8_t)
101 * Frame length: length in bytes including Type (uint8_t)
107 struct crsfPayloadRcChannelsPacked_s
{
108 // 176 bits of data (11 bits per channel * 16 channels) = 22 bytes.
109 unsigned int chan0
: 11;
110 unsigned int chan1
: 11;
111 unsigned int chan2
: 11;
112 unsigned int chan3
: 11;
113 unsigned int chan4
: 11;
114 unsigned int chan5
: 11;
115 unsigned int chan6
: 11;
116 unsigned int chan7
: 11;
117 unsigned int chan8
: 11;
118 unsigned int chan9
: 11;
119 unsigned int chan10
: 11;
120 unsigned int chan11
: 11;
121 unsigned int chan12
: 11;
122 unsigned int chan13
: 11;
123 unsigned int chan14
: 11;
124 unsigned int chan15
: 11;
125 } __attribute__ ((__packed__
));
127 typedef struct crsfPayloadRcChannelsPacked_s crsfPayloadRcChannelsPacked_t
;
130 * SUBSET RC FRAME 0x17
132 * The structure of 0x17 frame consists of 8-bit configuration data & variable length packed channel data.
134 * definition of the configuration byte
135 * bits 0-4: number of first channel packed
136 * bits 5-6: resolution configuration of the channel data (00 -> 10 bits, 01 -> 11 bits, 10 -> 12 bits, 11 -> 13 bits)
139 * data structure of the channel data
140 * - first channel packed with specified resolution
141 * - second channel packed with specified resolution
142 * - third channel packed with specified resolution
144 * - last channel packed with specified resolution
148 #if defined(USE_CRSF_LINK_STATISTICS)
150 * 0x14 Link statistics
153 * uint8_t Uplink RSSI Ant. 1 ( dBm * -1 )
154 * uint8_t Uplink RSSI Ant. 2 ( dBm * -1 )
155 * uint8_t Uplink Package success rate / Link quality ( % )
156 * int8_t Uplink SNR ( db )
157 * uint8_t Diversity active antenna ( enum ant. 1 = 0, ant. 2 )
158 * uint8_t RF Mode ( enum 4fps = 0 , 50fps, 150hz)
159 * uint8_t Uplink TX Power ( enum 0mW = 0, 10mW, 25 mW, 100 mW, 500 mW, 1000 mW, 2000mW, 250mW )
160 * uint8_t Downlink RSSI ( dBm * -1 )
161 * uint8_t Downlink package success rate / Link quality ( % )
162 * int8_t Downlink SNR ( db )
163 * Uplink is the connection from the ground to the UAV and downlink the opposite direction.
167 * 0x1C Link statistics RX
170 * uint8_t Downlink RSSI ( dBm * -1 )
171 * uint8_t Downlink RSSI ( % )
172 * uint8_t Downlink Package success rate / Link quality ( % )
173 * int8_t Downlink SNR ( db )
174 * uint8_t Uplink RF Power ( db )
178 * 0x1D Link statistics TX
181 * uint8_t Uplink RSSI ( dBm * -1 )
182 * uint8_t Uplink RSSI ( % )
183 * uint8_t Uplink Package success rate / Link quality ( % )
184 * int8_t Uplink SNR ( db )
185 * uint8_t Downlink RF Power ( db )
186 * uint8_t Uplink FPS ( FPS / 10 )
189 typedef struct crsfPayloadLinkstatistics_s
{
190 uint8_t uplink_RSSI_1
;
191 uint8_t uplink_RSSI_2
;
192 uint8_t uplink_Link_quality
;
194 uint8_t active_antenna
;
196 uint8_t uplink_TX_Power
;
197 uint8_t downlink_RSSI
;
198 uint8_t downlink_Link_quality
;
200 } crsfLinkStatistics_t
;
202 #if defined(USE_CRSF_V3)
203 typedef struct crsfPayloadLinkstatisticsRx_s
{
204 uint8_t downlink_RSSI_1
;
205 uint8_t downlink_RSSI_1_percentage
;
206 uint8_t downlink_Link_quality
;
208 uint8_t uplink_power
;
209 } crsfLinkStatisticsRx_t
; // this struct is currently not used
211 typedef struct crsfPayloadLinkstatisticsTx_s
{
213 uint8_t uplink_RSSI_percentage
;
214 uint8_t uplink_Link_quality
;
216 uint8_t downlink_power
; // currently not used
217 uint8_t uplink_FPS
; // currently not used
218 } crsfLinkStatisticsTx_t
;
221 static timeUs_t lastLinkStatisticsFrameUs
;
223 static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t
* statsPtr
, timeUs_t currentTimeUs
)
225 const crsfLinkStatistics_t stats
= *statsPtr
;
226 lastLinkStatisticsFrameUs
= currentTimeUs
;
227 int16_t rssiDbm
= -1 * (stats
.active_antenna
? stats
.uplink_RSSI_2
: stats
.uplink_RSSI_1
);
228 if (rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) {
229 if (rxConfig()->crsf_use_rx_snr
) {
230 // -10dB of SNR mapped to 0 RSSI (fail safe is likely to happen at this measure)
231 // 0dB of SNR mapped to 20 RSSI (default alarm)
232 // 41dB of SNR mapped to 99 RSSI (SNR can climb to around 60, but showing that is not very meaningful)
233 const uint16_t rsnrPercentScaled
= constrain((stats
.uplink_SNR
+ 10) * 20, 0, RSSI_MAX_VALUE
);
234 setRssi(rsnrPercentScaled
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
235 #ifdef USE_RX_RSSI_DBM
236 rssiDbm
= stats
.uplink_SNR
;
239 const uint16_t rssiPercentScaled
= scaleRange(rssiDbm
, CRSF_RSSI_MIN
, 0, 0, RSSI_MAX_VALUE
);
240 setRssi(rssiPercentScaled
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
243 #ifdef USE_RX_RSSI_DBM
244 setRssiDbm(rssiDbm
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
247 #ifdef USE_RX_LINK_QUALITY_INFO
248 if (linkQualitySource
== LQ_SOURCE_RX_PROTOCOL_CRSF
) {
249 setLinkQualityDirect(stats
.uplink_Link_quality
);
250 rxSetRfMode(stats
.rf_Mode
);
254 #ifdef USE_RX_LINK_UPLINK_POWER
255 const uint8_t crsfUplinkPowerStatesItemIndex
= (stats
.uplink_TX_Power
< CRSF_UPLINK_POWER_LEVEL_MW_ITEMS_COUNT
) ? stats
.uplink_TX_Power
: 0;
256 rxSetUplinkTxPwrMw(uplinkTXPowerStatesMw
[crsfUplinkPowerStatesItemIndex
]);
259 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 0, stats
.uplink_RSSI_1
);
260 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 1, stats
.uplink_RSSI_2
);
261 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 2, stats
.uplink_Link_quality
);
262 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 3, stats
.rf_Mode
);
264 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_PWR
, 0, stats
.active_antenna
);
265 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_PWR
, 1, stats
.uplink_SNR
);
266 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_PWR
, 2, stats
.uplink_TX_Power
);
268 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_DOWN
, 0, stats
.downlink_RSSI
);
269 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_DOWN
, 1, stats
.downlink_Link_quality
);
270 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_DOWN
, 2, stats
.downlink_SNR
);
273 #if defined(USE_CRSF_V3)
274 static void handleCrsfLinkStatisticsTxFrame(const crsfLinkStatisticsTx_t
* statsPtr
, timeUs_t currentTimeUs
)
276 const crsfLinkStatisticsTx_t stats
= *statsPtr
;
277 lastLinkStatisticsFrameUs
= currentTimeUs
;
278 if (rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) {
279 const uint16_t rssiPercentScaled
= scaleRange(stats
.uplink_RSSI_percentage
, 0, 100, 0, RSSI_MAX_VALUE
);
280 setRssi(rssiPercentScaled
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
282 #ifdef USE_RX_RSSI_DBM
283 int16_t rssiDbm
= -1 * stats
.uplink_RSSI
;
284 if (rxConfig()->crsf_use_rx_snr
) {
285 rssiDbm
= stats
.uplink_SNR
;
287 setRssiDbm(rssiDbm
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
290 #ifdef USE_RX_LINK_QUALITY_INFO
291 if (linkQualitySource
== LQ_SOURCE_RX_PROTOCOL_CRSF
) {
292 setLinkQualityDirect(stats
.uplink_Link_quality
);
296 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 0, stats
.uplink_RSSI
);
297 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 1, stats
.uplink_SNR
);
298 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 2, stats
.uplink_Link_quality
);
299 DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK
, 3, stats
.uplink_RSSI_percentage
);
304 #if defined(USE_CRSF_LINK_STATISTICS)
305 static void crsfCheckRssi(uint32_t currentTimeUs
) {
307 if (cmpTimeUs(currentTimeUs
, lastLinkStatisticsFrameUs
) > CRSF_LINK_STATUS_UPDATE_TIMEOUT_US
) {
308 if (rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) {
309 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
310 #ifdef USE_RX_RSSI_DBM
311 if (rxConfig()->crsf_use_rx_snr
) {
312 setRssiDbmDirect(CRSF_SNR_MIN
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
314 setRssiDbmDirect(CRSF_RSSI_MIN
, RSSI_SOURCE_RX_PROTOCOL_CRSF
);
318 #ifdef USE_RX_LINK_QUALITY_INFO
319 if (linkQualitySource
== LQ_SOURCE_RX_PROTOCOL_CRSF
) {
320 setLinkQualityDirect(0);
327 STATIC_UNIT_TESTED
uint8_t crsfFrameCRC(void)
329 // CRC includes type and payload
330 uint8_t crc
= crc8_dvb_s2(0, crsfFrame
.frame
.type
);
331 for (int ii
= 0; ii
< crsfFrame
.frame
.frameLength
- CRSF_FRAME_LENGTH_TYPE_CRC
; ++ii
) {
332 crc
= crc8_dvb_s2(crc
, crsfFrame
.frame
.payload
[ii
]);
337 STATIC_UNIT_TESTED
uint8_t crsfFrameCmdCRC(void)
339 // CRC includes type and payload
340 uint8_t crc
= crc8_poly_0xba(0, crsfFrame
.frame
.type
);
341 for (int ii
= 0; ii
< crsfFrame
.frame
.frameLength
- CRSF_FRAME_LENGTH_TYPE_CRC
- 1; ++ii
) {
342 crc
= crc8_poly_0xba(crc
, crsfFrame
.frame
.payload
[ii
]);
347 // Receive ISR callback, called back from serial port
348 STATIC_UNIT_TESTED
void crsfDataReceive(uint16_t c
, void *data
)
350 rxRuntimeState_t
*const rxRuntimeState
= (rxRuntimeState_t
*const)data
;
352 static uint8_t crsfFramePosition
= 0;
353 #if defined(USE_CRSF_V3)
354 static uint8_t crsfFrameErrorCnt
= 0;
356 const timeUs_t currentTimeUs
= microsISR();
358 #ifdef DEBUG_CRSF_PACKETS
359 debug
[2] = currentTimeUs
- crsfFrameStartAtUs
;
362 if (cmpTimeUs(currentTimeUs
, crsfFrameStartAtUs
) > CRSF_TIME_NEEDED_PER_FRAME_US
) {
363 // We've received a character after max time needed to complete a frame,
364 // so this must be the start of a new frame.
365 crsfFramePosition
= 0;
368 if (crsfFramePosition
== 0) {
369 crsfFrameStartAtUs
= currentTimeUs
;
371 // assume frame is 5 bytes long until we have received the frame length
372 // full frame length includes the length of the address and framelength fields
373 // sometimes we can receive some garbage data. So, we need to check max size for preventing buffer overrun.
374 const int fullFrameLength
= crsfFramePosition
< 3 ? 5 : MIN(crsfFrame
.frame
.frameLength
+ CRSF_FRAME_LENGTH_ADDRESS
+ CRSF_FRAME_LENGTH_FRAMELENGTH
, CRSF_FRAME_SIZE_MAX
);
376 if (crsfFramePosition
< fullFrameLength
) {
377 crsfFrame
.bytes
[crsfFramePosition
++] = (uint8_t)c
;
378 if (crsfFramePosition
>= fullFrameLength
) {
379 crsfFramePosition
= 0;
380 const uint8_t crc
= crsfFrameCRC();
381 if (crc
== crsfFrame
.bytes
[fullFrameLength
- 1]) {
382 #if defined(USE_CRSF_V3)
383 crsfFrameErrorCnt
= 0;
385 switch (crsfFrame
.frame
.type
) {
386 case CRSF_FRAMETYPE_RC_CHANNELS_PACKED
:
387 case CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED
:
388 if (crsfFrame
.frame
.deviceAddress
== CRSF_ADDRESS_FLIGHT_CONTROLLER
) {
389 rxRuntimeState
->lastRcFrameTimeUs
= currentTimeUs
;
390 crsfFrameDone
= true;
391 memcpy(&crsfChannelDataFrame
, &crsfFrame
, sizeof(crsfFrame
));
395 #if defined(USE_TELEMETRY_CRSF) && defined(USE_MSP_OVER_TELEMETRY)
396 case CRSF_FRAMETYPE_MSP_REQ
:
397 case CRSF_FRAMETYPE_MSP_WRITE
: {
398 uint8_t *frameStart
= (uint8_t *)&crsfFrame
.frame
.payload
+ CRSF_FRAME_ORIGIN_DEST_SIZE
;
399 if (bufferCrsfMspFrame(frameStart
, crsfFrame
.frame
.frameLength
- 4)) {
400 crsfScheduleMspResponse(crsfFrame
.frame
.payload
[1]);
405 #if defined(USE_CRSF_CMS_TELEMETRY)
406 case CRSF_FRAMETYPE_DEVICE_PING
:
407 crsfScheduleDeviceInfoResponse();
409 case CRSF_FRAMETYPE_DISPLAYPORT_CMD
: {
410 uint8_t *frameStart
= (uint8_t *)&crsfFrame
.frame
.payload
+ CRSF_FRAME_ORIGIN_DEST_SIZE
;
411 crsfProcessDisplayPortCmd(frameStart
);
415 #if defined(USE_CRSF_LINK_STATISTICS)
417 case CRSF_FRAMETYPE_LINK_STATISTICS
: {
418 // if to FC and 10 bytes + CRSF_FRAME_ORIGIN_DEST_SIZE
419 if ((rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) &&
420 (crsfFrame
.frame
.deviceAddress
== CRSF_ADDRESS_FLIGHT_CONTROLLER
) &&
421 (crsfFrame
.frame
.frameLength
== CRSF_FRAME_ORIGIN_DEST_SIZE
+ CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE
)) {
422 const crsfLinkStatistics_t
* statsFrame
= (const crsfLinkStatistics_t
*)&crsfFrame
.frame
.payload
;
423 handleCrsfLinkStatisticsFrame(statsFrame
, currentTimeUs
);
427 #if defined(USE_CRSF_V3)
428 case CRSF_FRAMETYPE_LINK_STATISTICS_RX
: {
431 case CRSF_FRAMETYPE_LINK_STATISTICS_TX
: {
432 if ((rssiSource
== RSSI_SOURCE_RX_PROTOCOL_CRSF
) &&
433 (crsfFrame
.frame
.deviceAddress
== CRSF_ADDRESS_FLIGHT_CONTROLLER
) &&
434 (crsfFrame
.frame
.frameLength
== CRSF_FRAME_ORIGIN_DEST_SIZE
+ CRSF_FRAME_LINK_STATISTICS_TX_PAYLOAD_SIZE
)) {
435 const crsfLinkStatisticsTx_t
* statsFrame
= (const crsfLinkStatisticsTx_t
*)&crsfFrame
.frame
.payload
;
436 handleCrsfLinkStatisticsTxFrame(statsFrame
, currentTimeUs
);
442 #if defined(USE_CRSF_V3)
443 case CRSF_FRAMETYPE_COMMAND
:
444 if ((crsfFrame
.bytes
[fullFrameLength
- 2] == crsfFrameCmdCRC()) &&
445 (crsfFrame
.bytes
[3] == CRSF_ADDRESS_FLIGHT_CONTROLLER
)) {
446 crsfProcessCommand(crsfFrame
.frame
.payload
+ CRSF_FRAME_ORIGIN_DEST_SIZE
);
454 #if defined(USE_CRSF_V3)
455 if (crsfFrameErrorCnt
< CRSF_FRAME_ERROR_COUNT_THRESHOLD
)
460 #if defined(USE_CRSF_V3)
461 if (crsfFrameErrorCnt
< CRSF_FRAME_ERROR_COUNT_THRESHOLD
)
465 #if defined(USE_CRSF_V3)
466 if (crsfFrameErrorCnt
>= CRSF_FRAME_ERROR_COUNT_THRESHOLD
) {
467 // fall back to default speed if speed mismatch detected
468 setCrsfDefaultSpeed();
469 crsfFrameErrorCnt
= 0;
475 STATIC_UNIT_TESTED
uint8_t crsfFrameStatus(rxRuntimeState_t
*rxRuntimeState
)
477 UNUSED(rxRuntimeState
);
479 #if defined(USE_CRSF_LINK_STATISTICS)
480 crsfCheckRssi(micros());
483 crsfFrameDone
= false;
485 // unpack the RC channels
486 if (crsfChannelDataFrame
.frame
.type
== CRSF_FRAMETYPE_RC_CHANNELS_PACKED
) {
487 // use ordinary RC frame structure (0x16)
488 const crsfPayloadRcChannelsPacked_t
* const rcChannels
= (crsfPayloadRcChannelsPacked_t
*)&crsfChannelDataFrame
.frame
.payload
;
489 channelScale
= CRSF_RC_CHANNEL_SCALE_LEGACY
;
490 crsfChannelData
[0] = rcChannels
->chan0
;
491 crsfChannelData
[1] = rcChannels
->chan1
;
492 crsfChannelData
[2] = rcChannels
->chan2
;
493 crsfChannelData
[3] = rcChannels
->chan3
;
494 crsfChannelData
[4] = rcChannels
->chan4
;
495 crsfChannelData
[5] = rcChannels
->chan5
;
496 crsfChannelData
[6] = rcChannels
->chan6
;
497 crsfChannelData
[7] = rcChannels
->chan7
;
498 crsfChannelData
[8] = rcChannels
->chan8
;
499 crsfChannelData
[9] = rcChannels
->chan9
;
500 crsfChannelData
[10] = rcChannels
->chan10
;
501 crsfChannelData
[11] = rcChannels
->chan11
;
502 crsfChannelData
[12] = rcChannels
->chan12
;
503 crsfChannelData
[13] = rcChannels
->chan13
;
504 crsfChannelData
[14] = rcChannels
->chan14
;
505 crsfChannelData
[15] = rcChannels
->chan15
;
507 // use subset RC frame structure (0x17)
508 uint8_t readByteIndex
= 0;
509 const uint8_t *payload
= crsfChannelDataFrame
.frame
.payload
;
511 // get the configuration byte
512 uint8_t configByte
= payload
[readByteIndex
++];
514 // get the channel number of start channel
515 uint8_t startChannel
= configByte
& CRSF_SUBSET_RC_STARTING_CHANNEL_MASK
;
516 configByte
>>= CRSF_SUBSET_RC_STARTING_CHANNEL_BITS
;
518 // get the channel resolution settings
520 uint16_t channelMask
;
521 uint8_t channelRes
= configByte
& CRSF_SUBSET_RC_RES_CONFIGURATION_MASK
;
522 configByte
>>= CRSF_SUBSET_RC_RES_CONFIGURATION_BITS
;
523 switch (channelRes
) {
524 case CRSF_SUBSET_RC_RES_CONF_10B
:
525 channelBits
= CRSF_SUBSET_RC_RES_BITS_10B
;
526 channelMask
= CRSF_SUBSET_RC_RES_MASK_10B
;
527 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_10B
;
530 case CRSF_SUBSET_RC_RES_CONF_11B
:
531 channelBits
= CRSF_SUBSET_RC_RES_BITS_11B
;
532 channelMask
= CRSF_SUBSET_RC_RES_MASK_11B
;
533 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_11B
;
535 case CRSF_SUBSET_RC_RES_CONF_12B
:
536 channelBits
= CRSF_SUBSET_RC_RES_BITS_12B
;
537 channelMask
= CRSF_SUBSET_RC_RES_MASK_12B
;
538 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_12B
;
540 case CRSF_SUBSET_RC_RES_CONF_13B
:
541 channelBits
= CRSF_SUBSET_RC_RES_BITS_13B
;
542 channelMask
= CRSF_SUBSET_RC_RES_MASK_13B
;
543 channelScale
= CRSF_SUBSET_RC_CHANNEL_SCALE_13B
;
547 // do nothing for the reserved configuration bit
548 configByte
>>= CRSF_SUBSET_RC_RESERVED_CONFIGURATION_BITS
;
550 // calculate the number of channels packed
551 uint8_t numOfChannels
= ((crsfChannelDataFrame
.frame
.frameLength
- CRSF_FRAME_LENGTH_TYPE_CRC
- 1) * 8) / channelBits
;
553 // unpack the channel data
554 uint8_t bitsMerged
= 0;
555 uint32_t readValue
= 0;
556 for (uint8_t n
= 0; n
< numOfChannels
; n
++) {
557 while (bitsMerged
< channelBits
) {
558 uint8_t readByte
= payload
[readByteIndex
++];
559 readValue
|= ((uint32_t) readByte
) << bitsMerged
;
562 crsfChannelData
[startChannel
+ n
] = readValue
& channelMask
;
563 readValue
>>= channelBits
;
564 bitsMerged
-= channelBits
;
567 return RX_FRAME_COMPLETE
;
569 return RX_FRAME_PENDING
;
572 STATIC_UNIT_TESTED
float crsfReadRawRC(const rxRuntimeState_t
*rxRuntimeState
, uint8_t chan
)
574 UNUSED(rxRuntimeState
);
575 if (channelScale
== CRSF_RC_CHANNEL_SCALE_LEGACY
) {
576 /* conversion from RC value to PWM
582 * scale factor = (2012-988) / (1811-172) = 0.62477120195241
583 * offset = 988 - 172 * 0.62477120195241 = 880.53935326418548
585 return (channelScale
* (float)crsfChannelData
[chan
]) + 881;
587 /* conversion from RC value to PWM
588 * for 0x17 Subset RC frame
590 return (channelScale
* (float)crsfChannelData
[chan
]) + 988;
594 void crsfRxWriteTelemetryData(const void *data
, int len
)
596 len
= MIN(len
, (int)sizeof(telemetryBuf
));
597 memcpy(telemetryBuf
, data
, len
);
598 telemetryBufLen
= len
;
601 void crsfRxSendTelemetryData(void)
603 // if there is telemetry data to write
604 if (telemetryBufLen
> 0) {
605 serialWriteBuf(serialPort
, telemetryBuf
, telemetryBufLen
);
606 telemetryBufLen
= 0; // reset telemetry buffer
610 bool crsfRxIsTelemetryBufEmpty(void)
612 return telemetryBufLen
== 0;
615 bool crsfRxInit(const rxConfig_t
*rxConfig
, rxRuntimeState_t
*rxRuntimeState
)
617 for (int ii
= 0; ii
< CRSF_MAX_CHANNEL
; ++ii
) {
618 crsfChannelData
[ii
] = (16 * rxConfig
->midrc
) / 10 - 1408;
621 rxRuntimeState
->channelCount
= CRSF_MAX_CHANNEL
;
622 rxRuntimeState
->rxRefreshRate
= CRSF_TIME_BETWEEN_FRAMES_US
; //!!TODO this needs checking
624 rxRuntimeState
->rcReadRawFn
= crsfReadRawRC
;
625 rxRuntimeState
->rcFrameStatusFn
= crsfFrameStatus
;
626 rxRuntimeState
->rcFrameTimeUsFn
= rxFrameTimeUs
;
628 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
633 serialPort
= openSerialPort(portConfig
->identifier
,
639 CRSF_PORT_OPTIONS
| (rxConfig
->serialrx_inverted
? SERIAL_INVERTED
: 0)
642 if (rssiSource
== RSSI_SOURCE_NONE
) {
643 rssiSource
= RSSI_SOURCE_RX_PROTOCOL_CRSF
;
645 #ifdef USE_RX_LINK_QUALITY_INFO
646 if (linkQualitySource
== LQ_SOURCE_NONE
) {
647 linkQualitySource
= LQ_SOURCE_RX_PROTOCOL_CRSF
;
651 return serialPort
!= NULL
;
654 #if defined(USE_CRSF_V3)
655 void crsfRxUpdateBaudrate(uint32_t baudrate
)
657 serialSetBaudRate(serialPort
, baudrate
);
661 bool crsfRxIsActive(void)
663 return serialPort
!= NULL
;