Merge pull request #6382 from mikeller/fix_smartport_delay
[betaflight.git] / src / main / rx / rx.c
blob347881a54c41753114221e576890b6b87892d36e
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>
25 #include <string.h>
27 #include "platform.h"
29 #include "build/build_config.h"
30 #include "build/debug.h"
32 #include "common/maths.h"
33 #include "common/utils.h"
35 #include "config/config_reset.h"
36 #include "config/feature.h"
38 #include "drivers/adc.h"
39 #include "drivers/rx/rx_pwm.h"
40 #include "drivers/rx/rx_spi.h"
41 #include "drivers/time.h"
43 #include "fc/config.h"
44 #include "fc/rc_controls.h"
45 #include "fc/rc_modes.h"
47 #include "flight/failsafe.h"
49 #include "io/serial.h"
51 #include "pg/pg.h"
52 #include "pg/pg_ids.h"
53 #include "pg/rx.h"
55 #include "rx/rx.h"
56 #include "rx/pwm.h"
57 #include "rx/fport.h"
58 #include "rx/sbus.h"
59 #include "rx/spektrum.h"
60 #include "rx/sumd.h"
61 #include "rx/sumh.h"
62 #include "rx/msp.h"
63 #include "rx/xbus.h"
64 #include "rx/ibus.h"
65 #include "rx/jetiexbus.h"
66 #include "rx/crsf.h"
67 #include "rx/rx_spi.h"
68 #include "rx/targetcustomserial.h"
71 const char rcChannelLetters[] = "AERT12345678abcdefgh";
73 static uint16_t rssi = 0; // range: [0;1023]
74 static timeUs_t lastMspRssiUpdateUs = 0;
76 #define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec
78 #define RSSI_ADC_DIVISOR (4096 / 1024)
79 #define RSSI_OFFSET_SCALING (1024 / 100.0f)
81 rssiSource_e rssiSource;
83 static bool rxDataProcessingRequired = false;
84 static bool auxiliaryProcessingRequired = false;
86 static bool rxSignalReceived = false;
87 static bool rxFlightChannelsValid = false;
88 static bool rxIsInFailsafeMode = true;
89 static uint8_t rxChannelCount;
91 static timeUs_t rxNextUpdateAtUs = 0;
92 static uint32_t needRxSignalBefore = 0;
93 static uint32_t needRxSignalMaxDelayUs;
94 static uint32_t suspendRxSignalUntil = 0;
95 static uint8_t skipRxSamples = 0;
97 static int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
98 int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
99 uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
101 #define MAX_INVALID_PULS_TIME 300
102 #define PPM_AND_PWM_SAMPLE_COUNT 3
104 #define DELAY_50_HZ (1000000 / 50)
105 #define DELAY_33_HZ (1000000 / 33)
106 #define DELAY_10_HZ (1000000 / 10)
107 #define DELAY_5_HZ (1000000 / 5)
108 #define SKIP_RC_ON_SUSPEND_PERIOD 1500000 // 1.5 second period in usec (call frequency independent)
109 #define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent)
111 rxRuntimeConfig_t rxRuntimeConfig;
112 static uint8_t rcSampleIndex = 0;
114 PG_REGISTER_ARRAY_WITH_RESET_FN(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs, PG_RX_CHANNEL_RANGE_CONFIG, 0);
115 void pgResetFn_rxChannelRangeConfigs(rxChannelRangeConfig_t *rxChannelRangeConfigs)
117 // set default calibration to full range and 1:1 mapping
118 for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
119 rxChannelRangeConfigs[i].min = PWM_RANGE_MIN;
120 rxChannelRangeConfigs[i].max = PWM_RANGE_MAX;
124 PG_REGISTER_ARRAY_WITH_RESET_FN(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs, PG_RX_FAILSAFE_CHANNEL_CONFIG, 0);
125 void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs)
127 for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
128 rxFailsafeChannelConfigs[i].mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
129 rxFailsafeChannelConfigs[i].step = (i == THROTTLE)
130 ? CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MIN_USEC)
131 : CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MID_USEC);
135 void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig) {
136 // set default calibration to full range and 1:1 mapping
137 for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
138 rxChannelRangeConfig->min = PWM_RANGE_MIN;
139 rxChannelRangeConfig->max = PWM_RANGE_MAX;
140 rxChannelRangeConfig++;
144 static uint16_t nullReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
146 UNUSED(rxRuntimeConfig);
147 UNUSED(channel);
149 return PPM_RCVR_TIMEOUT;
152 static uint8_t nullFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
154 UNUSED(rxRuntimeConfig);
156 return RX_FRAME_PENDING;
159 static bool nullProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
161 UNUSED(rxRuntimeConfig);
163 return true;
166 STATIC_UNIT_TESTED bool isPulseValid(uint16_t pulseDuration)
168 return pulseDuration >= rxConfig()->rx_min_usec &&
169 pulseDuration <= rxConfig()->rx_max_usec;
172 #ifdef USE_SERIAL_RX
173 bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
175 bool enabled = false;
176 switch (rxConfig->serialrx_provider) {
177 #ifdef USE_SERIALRX_SPEKTRUM
178 case SERIALRX_SRXL:
179 case SERIALRX_SPEKTRUM1024:
180 case SERIALRX_SPEKTRUM2048:
181 enabled = spektrumInit(rxConfig, rxRuntimeConfig);
182 break;
183 #endif
184 #ifdef USE_SERIALRX_SBUS
185 case SERIALRX_SBUS:
186 enabled = sbusInit(rxConfig, rxRuntimeConfig);
187 break;
188 #endif
189 #ifdef USE_SERIALRX_SUMD
190 case SERIALRX_SUMD:
191 enabled = sumdInit(rxConfig, rxRuntimeConfig);
192 break;
193 #endif
194 #ifdef USE_SERIALRX_SUMH
195 case SERIALRX_SUMH:
196 enabled = sumhInit(rxConfig, rxRuntimeConfig);
197 break;
198 #endif
199 #ifdef USE_SERIALRX_XBUS
200 case SERIALRX_XBUS_MODE_B:
201 case SERIALRX_XBUS_MODE_B_RJ01:
202 enabled = xBusInit(rxConfig, rxRuntimeConfig);
203 break;
204 #endif
205 #ifdef USE_SERIALRX_IBUS
206 case SERIALRX_IBUS:
207 enabled = ibusInit(rxConfig, rxRuntimeConfig);
208 break;
209 #endif
210 #ifdef USE_SERIALRX_JETIEXBUS
211 case SERIALRX_JETIEXBUS:
212 enabled = jetiExBusInit(rxConfig, rxRuntimeConfig);
213 break;
214 #endif
215 #ifdef USE_SERIALRX_CRSF
216 case SERIALRX_CRSF:
217 enabled = crsfRxInit(rxConfig, rxRuntimeConfig);
218 break;
219 #endif
220 #ifdef USE_SERIALRX_TARGET_CUSTOM
221 case SERIALRX_TARGET_CUSTOM:
222 enabled = targetCustomSerialRxInit(rxConfig, rxRuntimeConfig);
223 break;
224 #endif
225 #ifdef USE_SERIALRX_FPORT
226 case SERIALRX_FPORT:
227 enabled = fportRxInit(rxConfig, rxRuntimeConfig);
228 break;
229 #endif
230 default:
231 enabled = false;
232 break;
234 return enabled;
236 #endif
238 void rxInit(void)
240 rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
241 rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
242 rxRuntimeConfig.rcProcessFrameFn = nullProcessFrame;
243 rcSampleIndex = 0;
244 needRxSignalMaxDelayUs = DELAY_10_HZ;
246 for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
247 rcData[i] = rxConfig()->midrc;
248 rcInvalidPulsPeriod[i] = millis() + MAX_INVALID_PULS_TIME;
251 rcData[THROTTLE] = (feature(FEATURE_3D)) ? rxConfig()->midrc : rxConfig()->rx_min_usec;
253 // Initialize ARM switch to OFF position when arming via switch is defined
254 // TODO - move to rc_mode.c
255 for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
256 const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(i);
257 if (modeActivationCondition->modeId == BOXARM && IS_RANGE_USABLE(&modeActivationCondition->range)) {
258 // ARM switch is defined, determine an OFF value
259 uint16_t value;
260 if (modeActivationCondition->range.startStep > 0) {
261 value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.startStep - 1));
262 } else {
263 value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.endStep + 1));
265 // Initialize ARM AUX channel to OFF value
266 rcData[modeActivationCondition->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = value;
270 #ifdef USE_SERIAL_RX
271 if (feature(FEATURE_RX_SERIAL)) {
272 const bool enabled = serialRxInit(rxConfig(), &rxRuntimeConfig);
273 if (!enabled) {
274 featureClear(FEATURE_RX_SERIAL);
275 rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
276 rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
279 #endif
281 #ifdef USE_RX_MSP
282 if (feature(FEATURE_RX_MSP)) {
283 rxMspInit(rxConfig(), &rxRuntimeConfig);
284 needRxSignalMaxDelayUs = DELAY_5_HZ;
286 #endif
288 #ifdef USE_RX_SPI
289 if (feature(FEATURE_RX_SPI)) {
290 const bool enabled = rxSpiInit(rxSpiConfig(), &rxRuntimeConfig);
291 if (!enabled) {
292 featureClear(FEATURE_RX_SPI);
293 rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
294 rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
297 #endif
299 #if defined(USE_PWM) || defined(USE_PPM)
300 if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) {
301 rxPwmInit(rxConfig(), &rxRuntimeConfig);
303 #endif
305 #if defined(USE_ADC)
306 if (feature(FEATURE_RSSI_ADC)) {
307 rssiSource = RSSI_SOURCE_ADC;
308 } else
309 #endif
310 if (rxConfig()->rssi_channel > 0) {
311 rssiSource = RSSI_SOURCE_RX_CHANNEL;
314 rxChannelCount = MIN(rxConfig()->max_aux_channel + NON_AUX_CHANNEL_COUNT, rxRuntimeConfig.channelCount);
317 bool rxIsReceivingSignal(void)
319 return rxSignalReceived;
322 bool rxAreFlightChannelsValid(void)
324 return rxFlightChannelsValid;
327 void suspendRxSignal(void)
329 suspendRxSignalUntil = micros() + SKIP_RC_ON_SUSPEND_PERIOD;
330 skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
331 failsafeOnRxSuspend(SKIP_RC_ON_SUSPEND_PERIOD);
334 void resumeRxSignal(void)
336 suspendRxSignalUntil = micros();
337 skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
338 failsafeOnRxResume();
341 bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
343 UNUSED(currentDeltaTime);
345 bool signalReceived = false;
346 bool useDataDrivenProcessing = true;
348 #if defined(USE_PWM) || defined(USE_PPM)
349 if (feature(FEATURE_RX_PPM)) {
350 if (isPPMDataBeingReceived()) {
351 signalReceived = true;
352 rxIsInFailsafeMode = false;
353 needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs;
354 resetPPMDataReceivedState();
356 } else if (feature(FEATURE_RX_PARALLEL_PWM)) {
357 if (isPWMDataBeingReceived()) {
358 signalReceived = true;
359 rxIsInFailsafeMode = false;
360 needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs;
361 useDataDrivenProcessing = false;
363 } else
364 #endif
366 const uint8_t frameStatus = rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
367 if (frameStatus & RX_FRAME_COMPLETE) {
368 rxIsInFailsafeMode = (frameStatus & RX_FRAME_FAILSAFE) != 0;
369 bool rxFrameDropped = (frameStatus & RX_FRAME_DROPPED) != 0;
370 signalReceived = !(rxIsInFailsafeMode || rxFrameDropped);
371 if (signalReceived) {
372 needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs;
375 if (frameStatus & (RX_FRAME_FAILSAFE | RX_FRAME_DROPPED)) {
376 // No (0%) signal
377 setRssi(0, RSSI_SOURCE_FRAME_ERRORS);
378 } else {
379 // Valid (100%) signal
380 setRssi(RSSI_MAX_VALUE, RSSI_SOURCE_FRAME_ERRORS);
384 if (frameStatus & RX_FRAME_PROCESSING_REQUIRED) {
385 auxiliaryProcessingRequired = true;
389 if (signalReceived) {
390 rxSignalReceived = true;
391 } else if (currentTimeUs >= needRxSignalBefore) {
392 rxSignalReceived = false;
395 if ((signalReceived && useDataDrivenProcessing) || cmpTimeUs(currentTimeUs, rxNextUpdateAtUs) > 0) {
396 rxDataProcessingRequired = true;
399 return rxDataProcessingRequired || auxiliaryProcessingRequired; // data driven or 50Hz
402 static uint16_t calculateChannelMovingAverage(uint8_t chan, uint16_t sample)
404 static int16_t rcSamples[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT];
405 static int16_t rcDataMean[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT];
406 static bool rxSamplesCollected = false;
408 const uint8_t currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT;
410 // update the recent samples and compute the average of them
411 rcSamples[chan][currentSampleIndex] = sample;
413 // avoid returning an incorrect average which would otherwise occur before enough samples
414 if (!rxSamplesCollected) {
415 if (rcSampleIndex < PPM_AND_PWM_SAMPLE_COUNT) {
416 return sample;
418 rxSamplesCollected = true;
421 rcDataMean[chan] = 0;
422 for (int sampleIndex = 0; sampleIndex < PPM_AND_PWM_SAMPLE_COUNT; sampleIndex++) {
423 rcDataMean[chan] += rcSamples[chan][sampleIndex];
425 return rcDataMean[chan] / PPM_AND_PWM_SAMPLE_COUNT;
428 static uint16_t getRxfailValue(uint8_t channel)
430 const rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigs(channel);
432 switch (channelFailsafeConfig->mode) {
433 case RX_FAILSAFE_MODE_AUTO:
434 switch (channel) {
435 case ROLL:
436 case PITCH:
437 case YAW:
438 return rxConfig()->midrc;
439 case THROTTLE:
440 if (feature(FEATURE_3D))
441 return rxConfig()->midrc;
442 else
443 return rxConfig()->rx_min_usec;
445 /* no break */
447 default:
448 case RX_FAILSAFE_MODE_INVALID:
449 case RX_FAILSAFE_MODE_HOLD:
450 return rcData[channel];
452 case RX_FAILSAFE_MODE_SET:
453 return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step);
457 STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, const rxChannelRangeConfig_t *range)
459 // Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT
460 if (sample == PPM_RCVR_TIMEOUT) {
461 return PPM_RCVR_TIMEOUT;
464 sample = scaleRange(sample, range->min, range->max, PWM_RANGE_MIN, PWM_RANGE_MAX);
465 sample = constrain(sample, PWM_PULSE_MIN, PWM_PULSE_MAX);
467 return sample;
470 static void readRxChannelsApplyRanges(void)
472 for (int channel = 0; channel < rxChannelCount; channel++) {
474 const uint8_t rawChannel = channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel;
476 // sample the channel
477 uint16_t sample = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, rawChannel);
479 // apply the rx calibration
480 if (channel < NON_AUX_CHANNEL_COUNT) {
481 sample = applyRxChannelRangeConfiguraton(sample, rxChannelRangeConfigs(channel));
484 rcRaw[channel] = sample;
488 static void detectAndApplySignalLossBehaviour(void)
490 const uint32_t currentTimeMs = millis();
492 const bool useValueFromRx = rxSignalReceived && !rxIsInFailsafeMode;
494 DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 0, rxSignalReceived);
495 DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 1, rxIsInFailsafeMode);
497 rxFlightChannelsValid = true;
498 for (int channel = 0; channel < rxChannelCount; channel++) {
499 uint16_t sample = rcRaw[channel];
501 const bool validPulse = useValueFromRx && isPulseValid(sample);
503 if (validPulse) {
504 rcInvalidPulsPeriod[channel] = currentTimeMs + MAX_INVALID_PULS_TIME;
505 } else {
506 if (cmp32(currentTimeMs, rcInvalidPulsPeriod[channel]) < 0) {
507 continue; // skip to next channel to hold channel value MAX_INVALID_PULS_TIME
508 } else {
509 sample = getRxfailValue(channel); // after that apply rxfail value
510 if (channel < NON_AUX_CHANNEL_COUNT) {
511 rxFlightChannelsValid = false;
515 if (feature(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM)) {
516 // smooth output for PWM and PPM
517 rcData[channel] = calculateChannelMovingAverage(channel, sample);
518 } else {
519 rcData[channel] = sample;
523 if (rxFlightChannelsValid && !IS_RC_MODE_ACTIVE(BOXFAILSAFE)) {
524 failsafeOnValidDataReceived();
525 } else {
526 rxIsInFailsafeMode = true;
527 failsafeOnValidDataFailed();
528 for (int channel = 0; channel < rxChannelCount; channel++) {
529 rcData[channel] = getRxfailValue(channel);
532 DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 3, rcData[THROTTLE]);
535 bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
537 if (auxiliaryProcessingRequired) {
538 auxiliaryProcessingRequired = !rxRuntimeConfig.rcProcessFrameFn(&rxRuntimeConfig);
541 if (!rxDataProcessingRequired) {
542 return false;
545 rxDataProcessingRequired = false;
546 rxNextUpdateAtUs = currentTimeUs + DELAY_33_HZ;
548 // only proceed when no more samples to skip and suspend period is over
549 if (skipRxSamples) {
550 if (currentTimeUs > suspendRxSignalUntil) {
551 skipRxSamples--;
554 return true;
557 readRxChannelsApplyRanges();
558 detectAndApplySignalLossBehaviour();
560 rcSampleIndex++;
562 return true;
565 void parseRcChannels(const char *input, rxConfig_t *rxConfig)
567 for (const char *c = input; *c; c++) {
568 const char *s = strchr(rcChannelLetters, *c);
569 if (s && (s < rcChannelLetters + RX_MAPPABLE_CHANNEL_COUNT)) {
570 rxConfig->rcmap[s - rcChannelLetters] = c - input;
575 void setRssiDirect(uint16_t newRssi, rssiSource_e source)
577 if (source != rssiSource) {
578 return;
581 rssi = newRssi;
584 #define RSSI_SAMPLE_COUNT 16
586 void setRssi(uint16_t rssiValue, rssiSource_e source)
588 if (source != rssiSource) {
589 return;
592 static uint16_t rssiSamples[RSSI_SAMPLE_COUNT];
593 static uint8_t rssiSampleIndex = 0;
594 static unsigned sum = 0;
596 sum = sum + rssiValue;
597 sum = sum - rssiSamples[rssiSampleIndex];
598 rssiSamples[rssiSampleIndex] = rssiValue;
599 rssiSampleIndex = (rssiSampleIndex + 1) % RSSI_SAMPLE_COUNT;
601 int16_t rssiMean = sum / RSSI_SAMPLE_COUNT;
603 rssi = rssiMean;
606 void setRssiMsp(uint8_t newMspRssi)
608 if (rssiSource == RSSI_SOURCE_NONE) {
609 rssiSource = RSSI_SOURCE_MSP;
612 if (rssiSource == RSSI_SOURCE_MSP) {
613 rssi = ((uint16_t)newMspRssi) << 2;
614 lastMspRssiUpdateUs = micros();
618 static void updateRSSIPWM(void)
620 // Read value of AUX channel as rssi
621 int16_t pwmRssi = rcData[rxConfig()->rssi_channel - 1];
623 // RSSI_Invert option
624 if (rxConfig()->rssi_invert) {
625 pwmRssi = ((2000 - pwmRssi) + 1000);
628 // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
629 setRssiDirect(constrain(((pwmRssi - 1000) / 1000.0f) * RSSI_MAX_VALUE, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_CHANNEL);
632 static void updateRSSIADC(timeUs_t currentTimeUs)
634 #ifndef USE_ADC
635 UNUSED(currentTimeUs);
636 #else
637 static uint32_t rssiUpdateAt = 0;
639 if ((int32_t)(currentTimeUs - rssiUpdateAt) < 0) {
640 return;
642 rssiUpdateAt = currentTimeUs + DELAY_50_HZ;
644 const uint16_t adcRssiSample = adcGetChannel(ADC_RSSI);
645 uint16_t rssiValue = adcRssiSample / RSSI_ADC_DIVISOR;
647 // RSSI_Invert option
648 if (rxConfig()->rssi_invert) {
649 rssiValue = RSSI_MAX_VALUE - rssiValue;
652 setRssi(rssiValue, RSSI_SOURCE_ADC);
653 #endif
656 void updateRSSI(timeUs_t currentTimeUs)
658 switch (rssiSource) {
659 case RSSI_SOURCE_RX_CHANNEL:
660 updateRSSIPWM();
661 break;
662 case RSSI_SOURCE_ADC:
663 updateRSSIADC(currentTimeUs);
664 break;
665 case RSSI_SOURCE_MSP:
666 if (cmpTimeUs(micros(), lastMspRssiUpdateUs) > MSP_RSSI_TIMEOUT_US) {
667 rssi = 0;
669 break;
670 default:
671 break;
675 uint16_t getRssi(void)
677 return rxConfig()->rssi_scale / 100.0f * rssi + rxConfig()->rssi_offset * RSSI_OFFSET_SCALING;
680 uint8_t getRssiPercent(void)
682 return scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 100);
685 uint16_t rxGetRefreshRate(void)
687 return rxRuntimeConfig.rxRefreshRate;