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/>.
29 #include "build/build_config.h"
30 #include "build/debug.h"
32 #include "common/maths.h"
33 #include "common/utils.h"
34 #include "common/filter.h"
36 #include "config/config_reset.h"
37 #include "config/feature.h"
39 #include "drivers/adc.h"
40 #include "drivers/rx/rx_pwm.h"
41 #include "drivers/rx/rx_spi.h"
42 #include "drivers/time.h"
44 #include "config/config.h"
45 #include "fc/rc_controls.h"
46 #include "fc/rc_modes.h"
48 #include "flight/failsafe.h"
50 #include "io/serial.h"
53 #include "pg/pg_ids.h"
60 #include "rx/spektrum.h"
67 #include "rx/jetiexbus.h"
69 #include "rx/rx_spi.h"
70 #include "rx/targetcustomserial.h"
73 const char rcChannelLetters
[] = "AERT12345678abcdefgh";
75 static uint16_t rssi
= 0; // range: [0;1023]
76 static uint8_t rssi_dbm
= 130; // range: [0;130] display 0 to -130
77 static timeUs_t lastMspRssiUpdateUs
= 0;
79 static pt1Filter_t frameErrFilter
;
81 #ifdef USE_RX_LINK_QUALITY_INFO
82 static uint16_t linkQuality
= 0;
85 #define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec
87 #define RSSI_ADC_DIVISOR (4096 / 1024)
88 #define RSSI_OFFSET_SCALING (1024 / 100.0f)
90 rssiSource_e rssiSource
;
91 linkQualitySource_e linkQualitySource
;
93 static bool rxDataProcessingRequired
= false;
94 static bool auxiliaryProcessingRequired
= false;
96 static bool rxSignalReceived
= false;
97 static bool rxFlightChannelsValid
= false;
98 static bool rxIsInFailsafeMode
= true;
99 static uint8_t rxChannelCount
;
101 static timeUs_t rxNextUpdateAtUs
= 0;
102 static uint32_t needRxSignalBefore
= 0;
103 static uint32_t needRxSignalMaxDelayUs
;
104 static uint32_t suspendRxSignalUntil
= 0;
105 static uint8_t skipRxSamples
= 0;
107 static int16_t rcRaw
[MAX_SUPPORTED_RC_CHANNEL_COUNT
]; // interval [1000;2000]
108 int16_t rcData
[MAX_SUPPORTED_RC_CHANNEL_COUNT
]; // interval [1000;2000]
109 uint32_t rcInvalidPulsPeriod
[MAX_SUPPORTED_RC_CHANNEL_COUNT
];
111 #define MAX_INVALID_PULS_TIME 300
112 #define PPM_AND_PWM_SAMPLE_COUNT 3
114 #define DELAY_50_HZ (1000000 / 50)
115 #define DELAY_33_HZ (1000000 / 33)
116 #define DELAY_10_HZ (1000000 / 10)
117 #define DELAY_5_HZ (1000000 / 5)
118 #define SKIP_RC_ON_SUSPEND_PERIOD 1500000 // 1.5 second period in usec (call frequency independent)
119 #define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent)
121 rxRuntimeState_t rxRuntimeState
;
122 static uint8_t rcSampleIndex
= 0;
124 PG_REGISTER_ARRAY_WITH_RESET_FN(rxChannelRangeConfig_t
, NON_AUX_CHANNEL_COUNT
, rxChannelRangeConfigs
, PG_RX_CHANNEL_RANGE_CONFIG
, 0);
125 void pgResetFn_rxChannelRangeConfigs(rxChannelRangeConfig_t
*rxChannelRangeConfigs
)
127 // set default calibration to full range and 1:1 mapping
128 for (int i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
129 rxChannelRangeConfigs
[i
].min
= PWM_RANGE_MIN
;
130 rxChannelRangeConfigs
[i
].max
= PWM_RANGE_MAX
;
134 PG_REGISTER_ARRAY_WITH_RESET_FN(rxFailsafeChannelConfig_t
, MAX_SUPPORTED_RC_CHANNEL_COUNT
, rxFailsafeChannelConfigs
, PG_RX_FAILSAFE_CHANNEL_CONFIG
, 0);
135 void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t
*rxFailsafeChannelConfigs
)
137 for (int i
= 0; i
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; i
++) {
138 rxFailsafeChannelConfigs
[i
].mode
= (i
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_MODE_AUTO
: RX_FAILSAFE_MODE_HOLD
;
139 rxFailsafeChannelConfigs
[i
].step
= (i
== THROTTLE
)
140 ? CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MIN_USEC
)
141 : CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MID_USEC
);
145 void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t
*rxChannelRangeConfig
) {
146 // set default calibration to full range and 1:1 mapping
147 for (int i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
148 rxChannelRangeConfig
->min
= PWM_RANGE_MIN
;
149 rxChannelRangeConfig
->max
= PWM_RANGE_MAX
;
150 rxChannelRangeConfig
++;
154 static uint16_t nullReadRawRC(const rxRuntimeState_t
*rxRuntimeState
, uint8_t channel
)
156 UNUSED(rxRuntimeState
);
159 return PPM_RCVR_TIMEOUT
;
162 static uint8_t nullFrameStatus(rxRuntimeState_t
*rxRuntimeState
)
164 UNUSED(rxRuntimeState
);
166 return RX_FRAME_PENDING
;
169 static bool nullProcessFrame(const rxRuntimeState_t
*rxRuntimeState
)
171 UNUSED(rxRuntimeState
);
176 STATIC_UNIT_TESTED
bool isPulseValid(uint16_t pulseDuration
)
178 return pulseDuration
>= rxConfig()->rx_min_usec
&&
179 pulseDuration
<= rxConfig()->rx_max_usec
;
183 static bool serialRxInit(const rxConfig_t
*rxConfig
, rxRuntimeState_t
*rxRuntimeState
)
185 bool enabled
= false;
186 switch (rxRuntimeState
->serialrxProvider
) {
187 #ifdef USE_SERIALRX_SRXL2
189 enabled
= srxl2RxInit(rxConfig
, rxRuntimeState
);
192 #ifdef USE_SERIALRX_SPEKTRUM
194 case SERIALRX_SPEKTRUM1024
:
195 case SERIALRX_SPEKTRUM2048
:
196 enabled
= spektrumInit(rxConfig
, rxRuntimeState
);
199 #ifdef USE_SERIALRX_SBUS
201 enabled
= sbusInit(rxConfig
, rxRuntimeState
);
204 #ifdef USE_SERIALRX_SUMD
206 enabled
= sumdInit(rxConfig
, rxRuntimeState
);
209 #ifdef USE_SERIALRX_SUMH
211 enabled
= sumhInit(rxConfig
, rxRuntimeState
);
214 #ifdef USE_SERIALRX_XBUS
215 case SERIALRX_XBUS_MODE_B
:
216 case SERIALRX_XBUS_MODE_B_RJ01
:
217 enabled
= xBusInit(rxConfig
, rxRuntimeState
);
220 #ifdef USE_SERIALRX_IBUS
222 enabled
= ibusInit(rxConfig
, rxRuntimeState
);
225 #ifdef USE_SERIALRX_JETIEXBUS
226 case SERIALRX_JETIEXBUS
:
227 enabled
= jetiExBusInit(rxConfig
, rxRuntimeState
);
230 #ifdef USE_SERIALRX_CRSF
232 enabled
= crsfRxInit(rxConfig
, rxRuntimeState
);
235 #ifdef USE_SERIALRX_TARGET_CUSTOM
236 case SERIALRX_TARGET_CUSTOM
:
237 enabled
= targetCustomSerialRxInit(rxConfig
, rxRuntimeState
);
240 #ifdef USE_SERIALRX_FPORT
242 enabled
= fportRxInit(rxConfig
, rxRuntimeState
);
255 if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM
)) {
256 rxRuntimeState
.rxProvider
= RX_PROVIDER_PARALLEL_PWM
;
257 } else if (featureIsEnabled(FEATURE_RX_PPM
)) {
258 rxRuntimeState
.rxProvider
= RX_PROVIDER_PPM
;
259 } else if (featureIsEnabled(FEATURE_RX_SERIAL
)) {
260 rxRuntimeState
.rxProvider
= RX_PROVIDER_SERIAL
;
261 } else if (featureIsEnabled(FEATURE_RX_MSP
)) {
262 rxRuntimeState
.rxProvider
= RX_PROVIDER_MSP
;
263 } else if (featureIsEnabled(FEATURE_RX_SPI
)) {
264 rxRuntimeState
.rxProvider
= RX_PROVIDER_SPI
;
266 rxRuntimeState
.rxProvider
= RX_PROVIDER_NONE
;
268 rxRuntimeState
.serialrxProvider
= rxConfig()->serialrx_provider
;
269 rxRuntimeState
.rcReadRawFn
= nullReadRawRC
;
270 rxRuntimeState
.rcFrameStatusFn
= nullFrameStatus
;
271 rxRuntimeState
.rcProcessFrameFn
= nullProcessFrame
;
273 needRxSignalMaxDelayUs
= DELAY_10_HZ
;
275 for (int i
= 0; i
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; i
++) {
276 rcData
[i
] = rxConfig()->midrc
;
277 rcInvalidPulsPeriod
[i
] = millis() + MAX_INVALID_PULS_TIME
;
280 rcData
[THROTTLE
] = (featureIsEnabled(FEATURE_3D
)) ? rxConfig()->midrc
: rxConfig()->rx_min_usec
;
282 // Initialize ARM switch to OFF position when arming via switch is defined
283 // TODO - move to rc_mode.c
284 for (int i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
285 const modeActivationCondition_t
*modeActivationCondition
= modeActivationConditions(i
);
286 if (modeActivationCondition
->modeId
== BOXARM
&& IS_RANGE_USABLE(&modeActivationCondition
->range
)) {
287 // ARM switch is defined, determine an OFF value
289 if (modeActivationCondition
->range
.startStep
> 0) {
290 value
= MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition
->range
.startStep
- 1));
292 value
= MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition
->range
.endStep
+ 1));
294 // Initialize ARM AUX channel to OFF value
295 rcData
[modeActivationCondition
->auxChannelIndex
+ NON_AUX_CHANNEL_COUNT
] = value
;
299 switch (rxRuntimeState
.rxProvider
) {
304 case RX_PROVIDER_SERIAL
:
306 const bool enabled
= serialRxInit(rxConfig(), &rxRuntimeState
);
308 rxRuntimeState
.rcReadRawFn
= nullReadRawRC
;
309 rxRuntimeState
.rcFrameStatusFn
= nullFrameStatus
;
317 case RX_PROVIDER_MSP
:
318 rxMspInit(rxConfig(), &rxRuntimeState
);
319 needRxSignalMaxDelayUs
= DELAY_5_HZ
;
325 case RX_PROVIDER_SPI
:
327 const bool enabled
= rxSpiInit(rxSpiConfig(), &rxRuntimeState
);
329 rxRuntimeState
.rcReadRawFn
= nullReadRawRC
;
330 rxRuntimeState
.rcFrameStatusFn
= nullFrameStatus
;
337 #if defined(USE_PWM) || defined(USE_PPM)
338 case RX_PROVIDER_PPM
:
339 case RX_PROVIDER_PARALLEL_PWM
:
340 rxPwmInit(rxConfig(), &rxRuntimeState
);
347 if (featureIsEnabled(FEATURE_RSSI_ADC
)) {
348 rssiSource
= RSSI_SOURCE_ADC
;
351 if (rxConfig()->rssi_channel
> 0) {
352 rssiSource
= RSSI_SOURCE_RX_CHANNEL
;
355 // Setup source frame RSSI filtering to take averaged values every FRAME_ERR_RESAMPLE_US
356 pt1FilterInit(&frameErrFilter
, pt1FilterGain(GET_FRAME_ERR_LPF_FREQUENCY(rxConfig()->rssi_src_frame_lpf_period
), FRAME_ERR_RESAMPLE_US
/1000000.0));
358 rxChannelCount
= MIN(rxConfig()->max_aux_channel
+ NON_AUX_CHANNEL_COUNT
, rxRuntimeState
.channelCount
);
361 bool rxIsReceivingSignal(void)
363 return rxSignalReceived
;
366 bool rxAreFlightChannelsValid(void)
368 return rxFlightChannelsValid
;
371 void suspendRxPwmPpmSignal(void)
373 #if defined(USE_PWM) || defined(USE_PPM)
374 if (rxRuntimeState
.rxProvider
== RX_PROVIDER_PARALLEL_PWM
|| rxRuntimeState
.rxProvider
== RX_PROVIDER_PPM
) {
375 suspendRxSignalUntil
= micros() + SKIP_RC_ON_SUSPEND_PERIOD
;
376 skipRxSamples
= SKIP_RC_SAMPLES_ON_RESUME
;
377 failsafeOnRxSuspend(SKIP_RC_ON_SUSPEND_PERIOD
);
382 void resumeRxPwmPpmSignal(void)
384 #if defined(USE_PWM) || defined(USE_PPM)
385 if (rxRuntimeState
.rxProvider
== RX_PROVIDER_PARALLEL_PWM
|| rxRuntimeState
.rxProvider
== RX_PROVIDER_PPM
) {
386 suspendRxSignalUntil
= micros();
387 skipRxSamples
= SKIP_RC_SAMPLES_ON_RESUME
;
388 failsafeOnRxResume();
393 #ifdef USE_RX_LINK_QUALITY_INFO
394 #define LINK_QUALITY_SAMPLE_COUNT 16
396 STATIC_UNIT_TESTED
uint16_t updateLinkQualitySamples(uint16_t value
)
398 static uint16_t samples
[LINK_QUALITY_SAMPLE_COUNT
];
399 static uint8_t sampleIndex
= 0;
400 static uint16_t sum
= 0;
402 sum
+= value
- samples
[sampleIndex
];
403 samples
[sampleIndex
] = value
;
404 sampleIndex
= (sampleIndex
+ 1) % LINK_QUALITY_SAMPLE_COUNT
;
405 return sum
/ LINK_QUALITY_SAMPLE_COUNT
;
409 static void setLinkQuality(bool validFrame
, timeDelta_t currentDeltaTime
)
411 #ifdef USE_RX_LINK_QUALITY_INFO
412 if (linkQualitySource
!= LQ_SOURCE_RX_PROTOCOL_CRSF
) {
413 // calculate new sample mean
414 linkQuality
= updateLinkQualitySamples(validFrame
? LINK_QUALITY_MAX_VALUE
: 0);
418 if (rssiSource
== RSSI_SOURCE_FRAME_ERRORS
) {
419 static uint16_t tot_rssi
= 0;
420 static uint16_t cnt_rssi
= 0;
421 static timeDelta_t resample_time
= 0;
423 resample_time
+= currentDeltaTime
;
424 tot_rssi
+= validFrame
? RSSI_MAX_VALUE
: 0;
427 if (resample_time
>= FRAME_ERR_RESAMPLE_US
) {
428 setRssi(tot_rssi
/ cnt_rssi
, rssiSource
);
431 resample_time
-= FRAME_ERR_RESAMPLE_US
;
436 void setLinkQualityDirect(uint16_t linkqualityValue
)
438 #ifdef USE_RX_LINK_QUALITY_INFO
439 linkQuality
= linkqualityValue
;
441 UNUSED(linkqualityValue
);
445 bool rxUpdateCheck(timeUs_t currentTimeUs
, timeDelta_t currentDeltaTime
)
447 bool signalReceived
= false;
448 bool useDataDrivenProcessing
= true;
450 switch (rxRuntimeState
.rxProvider
) {
454 #if defined(USE_PWM) || defined(USE_PPM)
455 case RX_PROVIDER_PPM
:
456 if (isPPMDataBeingReceived()) {
457 signalReceived
= true;
458 rxIsInFailsafeMode
= false;
459 needRxSignalBefore
= currentTimeUs
+ needRxSignalMaxDelayUs
;
460 resetPPMDataReceivedState();
464 case RX_PROVIDER_PARALLEL_PWM
:
465 if (isPWMDataBeingReceived()) {
466 signalReceived
= true;
467 rxIsInFailsafeMode
= false;
468 needRxSignalBefore
= currentTimeUs
+ needRxSignalMaxDelayUs
;
469 useDataDrivenProcessing
= false;
474 case RX_PROVIDER_SERIAL
:
475 case RX_PROVIDER_MSP
:
476 case RX_PROVIDER_SPI
:
478 const uint8_t frameStatus
= rxRuntimeState
.rcFrameStatusFn(&rxRuntimeState
);
479 if (frameStatus
& RX_FRAME_COMPLETE
) {
480 rxIsInFailsafeMode
= (frameStatus
& RX_FRAME_FAILSAFE
) != 0;
481 bool rxFrameDropped
= (frameStatus
& RX_FRAME_DROPPED
) != 0;
482 signalReceived
= !(rxIsInFailsafeMode
|| rxFrameDropped
);
483 if (signalReceived
) {
484 needRxSignalBefore
= currentTimeUs
+ needRxSignalMaxDelayUs
;
487 setLinkQuality(signalReceived
, currentDeltaTime
);
490 if (frameStatus
& RX_FRAME_PROCESSING_REQUIRED
) {
491 auxiliaryProcessingRequired
= true;
498 if (signalReceived
) {
499 rxSignalReceived
= true;
500 } else if (currentTimeUs
>= needRxSignalBefore
) {
501 rxSignalReceived
= false;
504 if ((signalReceived
&& useDataDrivenProcessing
) || cmpTimeUs(currentTimeUs
, rxNextUpdateAtUs
) > 0) {
505 rxDataProcessingRequired
= true;
508 return rxDataProcessingRequired
|| auxiliaryProcessingRequired
; // data driven or 50Hz
511 #if defined(USE_PWM) || defined(USE_PPM)
512 static uint16_t calculateChannelMovingAverage(uint8_t chan
, uint16_t sample
)
514 static int16_t rcSamples
[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT
][PPM_AND_PWM_SAMPLE_COUNT
];
515 static int16_t rcDataMean
[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT
];
516 static bool rxSamplesCollected
= false;
518 const uint8_t currentSampleIndex
= rcSampleIndex
% PPM_AND_PWM_SAMPLE_COUNT
;
520 // update the recent samples and compute the average of them
521 rcSamples
[chan
][currentSampleIndex
] = sample
;
523 // avoid returning an incorrect average which would otherwise occur before enough samples
524 if (!rxSamplesCollected
) {
525 if (rcSampleIndex
< PPM_AND_PWM_SAMPLE_COUNT
) {
528 rxSamplesCollected
= true;
531 rcDataMean
[chan
] = 0;
532 for (int sampleIndex
= 0; sampleIndex
< PPM_AND_PWM_SAMPLE_COUNT
; sampleIndex
++) {
533 rcDataMean
[chan
] += rcSamples
[chan
][sampleIndex
];
535 return rcDataMean
[chan
] / PPM_AND_PWM_SAMPLE_COUNT
;
539 static uint16_t getRxfailValue(uint8_t channel
)
541 const rxFailsafeChannelConfig_t
*channelFailsafeConfig
= rxFailsafeChannelConfigs(channel
);
543 switch (channelFailsafeConfig
->mode
) {
544 case RX_FAILSAFE_MODE_AUTO
:
549 return rxConfig()->midrc
;
551 if (featureIsEnabled(FEATURE_3D
) && !IS_RC_MODE_ACTIVE(BOX3D
) && !flight3DConfig()->switched_mode3d
) {
552 return rxConfig()->midrc
;
554 return rxConfig()->rx_min_usec
;
560 case RX_FAILSAFE_MODE_INVALID
:
561 case RX_FAILSAFE_MODE_HOLD
:
562 return rcData
[channel
];
564 case RX_FAILSAFE_MODE_SET
:
565 return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig
->step
);
569 STATIC_UNIT_TESTED
uint16_t applyRxChannelRangeConfiguraton(int sample
, const rxChannelRangeConfig_t
*range
)
571 // Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT
572 if (sample
== PPM_RCVR_TIMEOUT
) {
573 return PPM_RCVR_TIMEOUT
;
576 sample
= scaleRange(sample
, range
->min
, range
->max
, PWM_RANGE_MIN
, PWM_RANGE_MAX
);
577 sample
= constrain(sample
, PWM_PULSE_MIN
, PWM_PULSE_MAX
);
582 static void readRxChannelsApplyRanges(void)
584 for (int channel
= 0; channel
< rxChannelCount
; channel
++) {
586 const uint8_t rawChannel
= channel
< RX_MAPPABLE_CHANNEL_COUNT
? rxConfig()->rcmap
[channel
] : channel
;
588 // sample the channel
589 uint16_t sample
= rxRuntimeState
.rcReadRawFn(&rxRuntimeState
, rawChannel
);
591 // apply the rx calibration
592 if (channel
< NON_AUX_CHANNEL_COUNT
) {
593 sample
= applyRxChannelRangeConfiguraton(sample
, rxChannelRangeConfigs(channel
));
596 rcRaw
[channel
] = sample
;
600 static void detectAndApplySignalLossBehaviour(void)
602 const uint32_t currentTimeMs
= millis();
604 const bool useValueFromRx
= rxSignalReceived
&& !rxIsInFailsafeMode
;
606 DEBUG_SET(DEBUG_RX_SIGNAL_LOSS
, 0, rxSignalReceived
);
607 DEBUG_SET(DEBUG_RX_SIGNAL_LOSS
, 1, rxIsInFailsafeMode
);
609 rxFlightChannelsValid
= true;
610 for (int channel
= 0; channel
< rxChannelCount
; channel
++) {
611 uint16_t sample
= rcRaw
[channel
];
613 const bool validPulse
= useValueFromRx
&& isPulseValid(sample
);
616 rcInvalidPulsPeriod
[channel
] = currentTimeMs
+ MAX_INVALID_PULS_TIME
;
618 if (cmp32(currentTimeMs
, rcInvalidPulsPeriod
[channel
]) < 0) {
619 continue; // skip to next channel to hold channel value MAX_INVALID_PULS_TIME
621 sample
= getRxfailValue(channel
); // after that apply rxfail value
622 if (channel
< NON_AUX_CHANNEL_COUNT
) {
623 rxFlightChannelsValid
= false;
627 #if defined(USE_PWM) || defined(USE_PPM)
628 if (rxRuntimeState
.rxProvider
== RX_PROVIDER_PARALLEL_PWM
|| rxRuntimeState
.rxProvider
== RX_PROVIDER_PPM
) {
629 // smooth output for PWM and PPM
630 rcData
[channel
] = calculateChannelMovingAverage(channel
, sample
);
634 rcData
[channel
] = sample
;
638 if (rxFlightChannelsValid
&& !IS_RC_MODE_ACTIVE(BOXFAILSAFE
)) {
639 failsafeOnValidDataReceived();
641 rxIsInFailsafeMode
= true;
642 failsafeOnValidDataFailed();
643 for (int channel
= 0; channel
< rxChannelCount
; channel
++) {
644 rcData
[channel
] = getRxfailValue(channel
);
647 DEBUG_SET(DEBUG_RX_SIGNAL_LOSS
, 3, rcData
[THROTTLE
]);
650 bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs
)
652 if (auxiliaryProcessingRequired
) {
653 auxiliaryProcessingRequired
= !rxRuntimeState
.rcProcessFrameFn(&rxRuntimeState
);
656 if (!rxDataProcessingRequired
) {
660 rxDataProcessingRequired
= false;
661 rxNextUpdateAtUs
= currentTimeUs
+ DELAY_33_HZ
;
663 // only proceed when no more samples to skip and suspend period is over
664 if (skipRxSamples
|| currentTimeUs
<= suspendRxSignalUntil
) {
665 if (currentTimeUs
> suspendRxSignalUntil
) {
672 readRxChannelsApplyRanges();
673 detectAndApplySignalLossBehaviour();
680 void parseRcChannels(const char *input
, rxConfig_t
*rxConfig
)
682 for (const char *c
= input
; *c
; c
++) {
683 const char *s
= strchr(rcChannelLetters
, *c
);
684 if (s
&& (s
< rcChannelLetters
+ RX_MAPPABLE_CHANNEL_COUNT
)) {
685 rxConfig
->rcmap
[s
- rcChannelLetters
] = c
- input
;
690 void setRssiDirect(uint16_t newRssi
, rssiSource_e source
)
692 if (source
!= rssiSource
) {
699 #define RSSI_SAMPLE_COUNT 16
701 static uint16_t updateRssiSamples(uint16_t value
)
703 static uint16_t samples
[RSSI_SAMPLE_COUNT
];
704 static uint8_t sampleIndex
= 0;
705 static unsigned sum
= 0;
707 sum
+= value
- samples
[sampleIndex
];
708 samples
[sampleIndex
] = value
;
709 sampleIndex
= (sampleIndex
+ 1) % RSSI_SAMPLE_COUNT
;
710 return sum
/ RSSI_SAMPLE_COUNT
;
713 void setRssi(uint16_t rssiValue
, rssiSource_e source
)
715 if (source
!= rssiSource
) {
720 if (source
== RSSI_SOURCE_FRAME_ERRORS
) {
721 rssi
= pt1FilterApply(&frameErrFilter
, rssiValue
);
723 // calculate new sample mean
724 rssi
= updateRssiSamples(rssiValue
);
728 void setRssiMsp(uint8_t newMspRssi
)
730 if (rssiSource
== RSSI_SOURCE_NONE
) {
731 rssiSource
= RSSI_SOURCE_MSP
;
734 if (rssiSource
== RSSI_SOURCE_MSP
) {
735 rssi
= ((uint16_t)newMspRssi
) << 2;
736 lastMspRssiUpdateUs
= micros();
740 static void updateRSSIPWM(void)
742 // Read value of AUX channel as rssi
743 int16_t pwmRssi
= rcData
[rxConfig()->rssi_channel
- 1];
745 // RSSI_Invert option
746 if (rxConfig()->rssi_invert
) {
747 pwmRssi
= ((2000 - pwmRssi
) + 1000);
750 // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
751 setRssiDirect(constrain(((pwmRssi
- 1000) / 1000.0f
) * RSSI_MAX_VALUE
, 0, RSSI_MAX_VALUE
), RSSI_SOURCE_RX_CHANNEL
);
754 static void updateRSSIADC(timeUs_t currentTimeUs
)
757 UNUSED(currentTimeUs
);
759 static uint32_t rssiUpdateAt
= 0;
761 if ((int32_t)(currentTimeUs
- rssiUpdateAt
) < 0) {
764 rssiUpdateAt
= currentTimeUs
+ DELAY_50_HZ
;
766 const uint16_t adcRssiSample
= adcGetChannel(ADC_RSSI
);
767 uint16_t rssiValue
= adcRssiSample
/ RSSI_ADC_DIVISOR
;
769 // RSSI_Invert option
770 if (rxConfig()->rssi_invert
) {
771 rssiValue
= RSSI_MAX_VALUE
- rssiValue
;
774 setRssi(rssiValue
, RSSI_SOURCE_ADC
);
778 void updateRSSI(timeUs_t currentTimeUs
)
780 switch (rssiSource
) {
781 case RSSI_SOURCE_RX_CHANNEL
:
784 case RSSI_SOURCE_ADC
:
785 updateRSSIADC(currentTimeUs
);
787 case RSSI_SOURCE_MSP
:
788 if (cmpTimeUs(micros(), lastMspRssiUpdateUs
) > MSP_RSSI_TIMEOUT_US
) {
797 uint16_t getRssi(void)
799 return rxConfig()->rssi_scale
/ 100.0f
* rssi
+ rxConfig()->rssi_offset
* RSSI_OFFSET_SCALING
;
802 uint8_t getRssiPercent(void)
804 return scaleRange(getRssi(), 0, RSSI_MAX_VALUE
, 0, 100);
807 uint8_t getRssiDbm(void)
812 #define RSSI_SAMPLE_COUNT_DBM 16
814 static uint8_t updateRssiDbmSamples(uint8_t value
)
816 static uint16_t samplesdbm
[RSSI_SAMPLE_COUNT_DBM
];
817 static uint8_t sampledbmIndex
= 0;
818 static unsigned sumdbm
= 0;
820 sumdbm
+= value
- samplesdbm
[sampledbmIndex
];
821 samplesdbm
[sampledbmIndex
] = value
;
822 sampledbmIndex
= (sampledbmIndex
+ 1) % RSSI_SAMPLE_COUNT_DBM
;
823 return sumdbm
/ RSSI_SAMPLE_COUNT_DBM
;
826 void setRssiDbm(uint8_t rssiDbmValue
, rssiSource_e source
)
828 if (source
!= rssiSource
) {
832 rssi_dbm
= updateRssiDbmSamples(rssiDbmValue
);
835 void setRssiDbmDirect(uint8_t newRssiDbm
, rssiSource_e source
)
837 if (source
!= rssiSource
) {
841 rssi_dbm
= newRssiDbm
;
844 #ifdef USE_RX_LINK_QUALITY_INFO
845 uint16_t rxGetLinkQuality(void)
850 uint16_t rxGetLinkQualityPercent(void)
852 return (linkQualitySource
== LQ_SOURCE_RX_PROTOCOL_CRSF
) ? (linkQuality
/ 3.41) : scaleRange(linkQuality
, 0, LINK_QUALITY_MAX_VALUE
, 0, 100);
856 uint16_t rxGetRefreshRate(void)
858 return rxRuntimeState
.rxRefreshRate
;
861 bool isRssiConfigured(void)
863 return rssiSource
!= RSSI_SOURCE_NONE
;