2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
26 #include "build/build_config.h"
27 #include "build/debug.h"
29 #include "common/maths.h"
30 #include "common/utils.h"
32 #include "config/config_reset.h"
33 #include "config/feature.h"
35 #include "drivers/adc.h"
36 #include "drivers/rx/rx_pwm.h"
37 #include "drivers/rx/rx_spi.h"
38 #include "drivers/time.h"
40 #include "fc/config.h"
41 #include "fc/rc_controls.h"
42 #include "fc/rc_modes.h"
44 #include "flight/failsafe.h"
46 #include "io/serial.h"
49 #include "pg/pg_ids.h"
55 #include "rx/spektrum.h"
61 #include "rx/jetiexbus.h"
63 #include "rx/rx_spi.h"
64 #include "rx/targetcustomserial.h"
67 //#define DEBUG_RX_SIGNAL_LOSS
69 const char rcChannelLetters
[] = "AERT12345678abcdefgh";
71 static uint16_t rssi
= 0; // range: [0;1023]
72 static timeUs_t lastMspRssiUpdateUs
= 0;
74 #define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec
76 rssiSource_e rssiSource
;
78 static bool rxDataProcessingRequired
= false;
79 static bool auxiliaryProcessingRequired
= false;
81 static bool rxSignalReceived
= false;
82 static bool rxFlightChannelsValid
= false;
83 static bool rxIsInFailsafeMode
= true;
84 static uint8_t rxChannelCount
;
86 static timeUs_t rxNextUpdateAtUs
= 0;
87 static uint32_t needRxSignalBefore
= 0;
88 static uint32_t needRxSignalMaxDelayUs
;
89 static uint32_t suspendRxSignalUntil
= 0;
90 static uint8_t skipRxSamples
= 0;
92 static int16_t rcRaw
[MAX_SUPPORTED_RC_CHANNEL_COUNT
]; // interval [1000;2000]
93 int16_t rcData
[MAX_SUPPORTED_RC_CHANNEL_COUNT
]; // interval [1000;2000]
94 uint32_t rcInvalidPulsPeriod
[MAX_SUPPORTED_RC_CHANNEL_COUNT
];
96 #define MAX_INVALID_PULS_TIME 300
97 #define PPM_AND_PWM_SAMPLE_COUNT 3
99 #define DELAY_50_HZ (1000000 / 50)
100 #define DELAY_10_HZ (1000000 / 10)
101 #define DELAY_5_HZ (1000000 / 5)
102 #define SKIP_RC_ON_SUSPEND_PERIOD 1500000 // 1.5 second period in usec (call frequency independent)
103 #define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent)
105 rxRuntimeConfig_t rxRuntimeConfig
;
106 static uint8_t rcSampleIndex
= 0;
108 #ifndef RX_SPI_DEFAULT_PROTOCOL
109 #define RX_SPI_DEFAULT_PROTOCOL 0
111 #ifndef SERIALRX_PROVIDER
112 #define SERIALRX_PROVIDER 0
115 #define RX_MIN_USEC 885
116 #define RX_MAX_USEC 2115
117 #define RX_MID_USEC 1500
119 #ifndef SPEKTRUM_BIND_PIN
120 #define SPEKTRUM_BIND_PIN NONE
124 #define BINDPLUG_PIN NONE
127 PG_REGISTER_WITH_RESET_FN(rxConfig_t
, rxConfig
, PG_RX_CONFIG
, 2);
128 void pgResetFn_rxConfig(rxConfig_t
*rxConfig
)
130 RESET_CONFIG_2(rxConfig_t
, rxConfig
,
132 .serialrx_provider
= SERIALRX_PROVIDER
,
133 .rx_spi_protocol
= RX_SPI_DEFAULT_PROTOCOL
,
134 .serialrx_inverted
= 0,
135 .spektrum_bind_pin_override_ioTag
= IO_TAG(SPEKTRUM_BIND_PIN
),
136 .spektrum_bind_plug_ioTag
= IO_TAG(BINDPLUG_PIN
),
137 .spektrum_sat_bind
= 0,
138 .spektrum_sat_bind_autoreset
= 1,
139 .midrc
= RX_MID_USEC
,
142 .rx_min_usec
= RX_MIN_USEC
, // any of first 4 channels below this value will trigger rx loss detection
143 .rx_max_usec
= RX_MAX_USEC
, // any of first 4 channels above this value will trigger rx loss detection
144 .rssi_src_frame_errors
= true,
146 .rssi_scale
= RSSI_SCALE_DEFAULT
,
148 .rcInterpolation
= RC_SMOOTHING_AUTO
,
149 .rcInterpolationChannels
= 0,
150 .rcInterpolationInterval
= 19,
151 .fpvCamAngleDegrees
= 0,
152 .airModeActivateThreshold
= 32,
153 .max_aux_channel
= DEFAULT_AUX_CHANNEL_COUNT
156 #ifdef RX_CHANNELS_TAER
157 parseRcChannels("TAER1234", rxConfig
);
159 parseRcChannels("AETR1234", rxConfig
);
163 PG_REGISTER_ARRAY_WITH_RESET_FN(rxChannelRangeConfig_t
, NON_AUX_CHANNEL_COUNT
, rxChannelRangeConfigs
, PG_RX_CHANNEL_RANGE_CONFIG
, 0);
164 void pgResetFn_rxChannelRangeConfigs(rxChannelRangeConfig_t
*rxChannelRangeConfigs
)
166 // set default calibration to full range and 1:1 mapping
167 for (int i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
168 rxChannelRangeConfigs
[i
].min
= PWM_RANGE_MIN
;
169 rxChannelRangeConfigs
[i
].max
= PWM_RANGE_MAX
;
173 PG_REGISTER_ARRAY_WITH_RESET_FN(rxFailsafeChannelConfig_t
, MAX_SUPPORTED_RC_CHANNEL_COUNT
, rxFailsafeChannelConfigs
, PG_RX_FAILSAFE_CHANNEL_CONFIG
, 0);
174 void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t
*rxFailsafeChannelConfigs
)
176 for (int i
= 0; i
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; i
++) {
177 rxFailsafeChannelConfigs
[i
].mode
= (i
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_MODE_AUTO
: RX_FAILSAFE_MODE_HOLD
;
178 rxFailsafeChannelConfigs
[i
].step
= (i
== THROTTLE
)
179 ? CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MIN_USEC
)
180 : CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MID_USEC
);
184 void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t
*rxChannelRangeConfig
) {
185 // set default calibration to full range and 1:1 mapping
186 for (int i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
187 rxChannelRangeConfig
->min
= PWM_RANGE_MIN
;
188 rxChannelRangeConfig
->max
= PWM_RANGE_MAX
;
189 rxChannelRangeConfig
++;
193 static uint16_t nullReadRawRC(const rxRuntimeConfig_t
*rxRuntimeConfig
, uint8_t channel
)
195 UNUSED(rxRuntimeConfig
);
198 return PPM_RCVR_TIMEOUT
;
201 static uint8_t nullFrameStatus(rxRuntimeConfig_t
*rxRuntimeConfig
)
203 UNUSED(rxRuntimeConfig
);
205 return RX_FRAME_PENDING
;
208 static bool nullProcessFrame(const rxRuntimeConfig_t
*rxRuntimeConfig
)
210 UNUSED(rxRuntimeConfig
);
215 STATIC_UNIT_TESTED
bool isPulseValid(uint16_t pulseDuration
)
217 return pulseDuration
>= rxConfig()->rx_min_usec
&&
218 pulseDuration
<= rxConfig()->rx_max_usec
;
222 bool serialRxInit(const rxConfig_t
*rxConfig
, rxRuntimeConfig_t
*rxRuntimeConfig
)
224 bool enabled
= false;
225 switch (rxConfig
->serialrx_provider
) {
226 #ifdef USE_SERIALRX_SPEKTRUM
228 case SERIALRX_SPEKTRUM1024
:
229 case SERIALRX_SPEKTRUM2048
:
230 enabled
= spektrumInit(rxConfig
, rxRuntimeConfig
);
233 #ifdef USE_SERIALRX_SBUS
235 enabled
= sbusInit(rxConfig
, rxRuntimeConfig
);
238 #ifdef USE_SERIALRX_SUMD
240 enabled
= sumdInit(rxConfig
, rxRuntimeConfig
);
243 #ifdef USE_SERIALRX_SUMH
245 enabled
= sumhInit(rxConfig
, rxRuntimeConfig
);
248 #ifdef USE_SERIALRX_XBUS
249 case SERIALRX_XBUS_MODE_B
:
250 case SERIALRX_XBUS_MODE_B_RJ01
:
251 enabled
= xBusInit(rxConfig
, rxRuntimeConfig
);
254 #ifdef USE_SERIALRX_IBUS
256 enabled
= ibusInit(rxConfig
, rxRuntimeConfig
);
259 #ifdef USE_SERIALRX_JETIEXBUS
260 case SERIALRX_JETIEXBUS
:
261 enabled
= jetiExBusInit(rxConfig
, rxRuntimeConfig
);
264 #ifdef USE_SERIALRX_CRSF
266 enabled
= crsfRxInit(rxConfig
, rxRuntimeConfig
);
269 #ifdef USE_SERIALRX_TARGET_CUSTOM
270 case SERIALRX_TARGET_CUSTOM
:
271 enabled
= targetCustomSerialRxInit(rxConfig
, rxRuntimeConfig
);
274 #ifdef USE_SERIALRX_FPORT
276 enabled
= fportRxInit(rxConfig
, rxRuntimeConfig
);
289 rxRuntimeConfig
.rcReadRawFn
= nullReadRawRC
;
290 rxRuntimeConfig
.rcFrameStatusFn
= nullFrameStatus
;
291 rxRuntimeConfig
.rcProcessFrameFn
= nullProcessFrame
;
293 needRxSignalMaxDelayUs
= DELAY_10_HZ
;
295 for (int i
= 0; i
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; i
++) {
296 rcData
[i
] = rxConfig()->midrc
;
297 rcInvalidPulsPeriod
[i
] = millis() + MAX_INVALID_PULS_TIME
;
300 rcData
[THROTTLE
] = (feature(FEATURE_3D
)) ? rxConfig()->midrc
: rxConfig()->rx_min_usec
;
302 // Initialize ARM switch to OFF position when arming via switch is defined
303 // TODO - move to rc_mode.c
304 for (int i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
305 const modeActivationCondition_t
*modeActivationCondition
= modeActivationConditions(i
);
306 if (modeActivationCondition
->modeId
== BOXARM
&& IS_RANGE_USABLE(&modeActivationCondition
->range
)) {
307 // ARM switch is defined, determine an OFF value
309 if (modeActivationCondition
->range
.startStep
> 0) {
310 value
= MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition
->range
.startStep
- 1));
312 value
= MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition
->range
.endStep
+ 1));
314 // Initialize ARM AUX channel to OFF value
315 rcData
[modeActivationCondition
->auxChannelIndex
+ NON_AUX_CHANNEL_COUNT
] = value
;
320 if (feature(FEATURE_RX_SERIAL
)) {
321 const bool enabled
= serialRxInit(rxConfig(), &rxRuntimeConfig
);
323 featureClear(FEATURE_RX_SERIAL
);
324 rxRuntimeConfig
.rcReadRawFn
= nullReadRawRC
;
325 rxRuntimeConfig
.rcFrameStatusFn
= nullFrameStatus
;
331 if (feature(FEATURE_RX_MSP
)) {
332 rxMspInit(rxConfig(), &rxRuntimeConfig
);
333 needRxSignalMaxDelayUs
= DELAY_5_HZ
;
338 if (feature(FEATURE_RX_SPI
)) {
339 const bool enabled
= rxSpiInit(rxConfig(), &rxRuntimeConfig
);
341 featureClear(FEATURE_RX_SPI
);
342 rxRuntimeConfig
.rcReadRawFn
= nullReadRawRC
;
343 rxRuntimeConfig
.rcFrameStatusFn
= nullFrameStatus
;
348 #if defined(USE_PWM) || defined(USE_PPM)
349 if (feature(FEATURE_RX_PPM
) || feature(FEATURE_RX_PARALLEL_PWM
)) {
350 rxPwmInit(rxConfig(), &rxRuntimeConfig
);
355 if (feature(FEATURE_RSSI_ADC
)) {
356 rssiSource
= RSSI_SOURCE_ADC
;
359 if (rxConfig()->rssi_channel
> 0) {
360 rssiSource
= RSSI_SOURCE_RX_CHANNEL
;
363 rxChannelCount
= MIN(rxConfig()->max_aux_channel
+ NON_AUX_CHANNEL_COUNT
, rxRuntimeConfig
.channelCount
);
366 bool rxIsReceivingSignal(void)
368 return rxSignalReceived
;
371 bool rxAreFlightChannelsValid(void)
373 return rxFlightChannelsValid
;
376 void suspendRxSignal(void)
378 suspendRxSignalUntil
= micros() + SKIP_RC_ON_SUSPEND_PERIOD
;
379 skipRxSamples
= SKIP_RC_SAMPLES_ON_RESUME
;
380 failsafeOnRxSuspend(SKIP_RC_ON_SUSPEND_PERIOD
);
383 void resumeRxSignal(void)
385 suspendRxSignalUntil
= micros();
386 skipRxSamples
= SKIP_RC_SAMPLES_ON_RESUME
;
387 failsafeOnRxResume();
390 bool rxUpdateCheck(timeUs_t currentTimeUs
, timeDelta_t currentDeltaTime
)
392 UNUSED(currentDeltaTime
);
394 if (rxSignalReceived
) {
395 if (currentTimeUs
>= needRxSignalBefore
) {
396 rxSignalReceived
= false;
400 #if defined(USE_PWM) || defined(USE_PPM)
401 if (feature(FEATURE_RX_PPM
)) {
402 if (isPPMDataBeingReceived()) {
403 rxDataProcessingRequired
= true;
404 rxSignalReceived
= true;
405 rxIsInFailsafeMode
= false;
406 needRxSignalBefore
= currentTimeUs
+ needRxSignalMaxDelayUs
;
407 resetPPMDataReceivedState();
409 } else if (feature(FEATURE_RX_PARALLEL_PWM
)) {
410 if (isPWMDataBeingReceived()) {
411 rxDataProcessingRequired
= true;
412 rxSignalReceived
= true;
413 rxIsInFailsafeMode
= false;
414 needRxSignalBefore
= currentTimeUs
+ needRxSignalMaxDelayUs
;
419 const uint8_t frameStatus
= rxRuntimeConfig
.rcFrameStatusFn(&rxRuntimeConfig
);
420 if (frameStatus
& (RX_FRAME_COMPLETE
| RX_FRAME_FAILSAFE
| RX_FRAME_DROPPED
)) {
421 rxDataProcessingRequired
= true;
422 rxIsInFailsafeMode
= (frameStatus
& RX_FRAME_FAILSAFE
) != 0;
423 rxSignalReceived
= (frameStatus
& RX_FRAME_COMPLETE
) != 0;
424 needRxSignalBefore
= currentTimeUs
+ needRxSignalMaxDelayUs
;
426 if (frameStatus
& RX_FRAME_DROPPED
) {
428 setRssiUnfiltered(0, RSSI_SOURCE_FRAME_ERRORS
);
430 // Valid (100%) signal
431 setRssiUnfiltered(RSSI_MAX_VALUE
, RSSI_SOURCE_FRAME_ERRORS
);
435 if (frameStatus
& RX_FRAME_PROCESSING_REQUIRED
) {
436 auxiliaryProcessingRequired
= true;
440 if (cmpTimeUs(currentTimeUs
, rxNextUpdateAtUs
) > 0) {
441 rxDataProcessingRequired
= true;
444 return rxDataProcessingRequired
|| auxiliaryProcessingRequired
; // data driven or 50Hz
447 static uint16_t calculateChannelMovingAverage(uint8_t chan
, uint16_t sample
)
449 static int16_t rcSamples
[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT
][PPM_AND_PWM_SAMPLE_COUNT
];
450 static int16_t rcDataMean
[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT
];
451 static bool rxSamplesCollected
= false;
453 const uint8_t currentSampleIndex
= rcSampleIndex
% PPM_AND_PWM_SAMPLE_COUNT
;
455 // update the recent samples and compute the average of them
456 rcSamples
[chan
][currentSampleIndex
] = sample
;
458 // avoid returning an incorrect average which would otherwise occur before enough samples
459 if (!rxSamplesCollected
) {
460 if (rcSampleIndex
< PPM_AND_PWM_SAMPLE_COUNT
) {
463 rxSamplesCollected
= true;
466 rcDataMean
[chan
] = 0;
467 for (int sampleIndex
= 0; sampleIndex
< PPM_AND_PWM_SAMPLE_COUNT
; sampleIndex
++) {
468 rcDataMean
[chan
] += rcSamples
[chan
][sampleIndex
];
470 return rcDataMean
[chan
] / PPM_AND_PWM_SAMPLE_COUNT
;
473 static uint16_t getRxfailValue(uint8_t channel
)
475 const rxFailsafeChannelConfig_t
*channelFailsafeConfig
= rxFailsafeChannelConfigs(channel
);
477 switch (channelFailsafeConfig
->mode
) {
478 case RX_FAILSAFE_MODE_AUTO
:
483 return rxConfig()->midrc
;
485 if (feature(FEATURE_3D
))
486 return rxConfig()->midrc
;
488 return rxConfig()->rx_min_usec
;
493 case RX_FAILSAFE_MODE_INVALID
:
494 case RX_FAILSAFE_MODE_HOLD
:
495 return rcData
[channel
];
497 case RX_FAILSAFE_MODE_SET
:
498 return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig
->step
);
502 STATIC_UNIT_TESTED
uint16_t applyRxChannelRangeConfiguraton(int sample
, const rxChannelRangeConfig_t
*range
)
504 // Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT
505 if (sample
== PPM_RCVR_TIMEOUT
) {
506 return PPM_RCVR_TIMEOUT
;
509 sample
= scaleRange(sample
, range
->min
, range
->max
, PWM_RANGE_MIN
, PWM_RANGE_MAX
);
510 sample
= constrain(sample
, PWM_PULSE_MIN
, PWM_PULSE_MAX
);
515 static void readRxChannelsApplyRanges(void)
517 for (int channel
= 0; channel
< rxChannelCount
; channel
++) {
519 const uint8_t rawChannel
= channel
< RX_MAPPABLE_CHANNEL_COUNT
? rxConfig()->rcmap
[channel
] : channel
;
521 // sample the channel
522 uint16_t sample
= rxRuntimeConfig
.rcReadRawFn(&rxRuntimeConfig
, rawChannel
);
524 // apply the rx calibration
525 if (channel
< NON_AUX_CHANNEL_COUNT
) {
526 sample
= applyRxChannelRangeConfiguraton(sample
, rxChannelRangeConfigs(channel
));
529 rcRaw
[channel
] = sample
;
533 static void detectAndApplySignalLossBehaviour(void)
535 const uint32_t currentTimeMs
= millis();
537 const bool useValueFromRx
= rxSignalReceived
&& !rxIsInFailsafeMode
;
539 #ifdef DEBUG_RX_SIGNAL_LOSS
540 debug
[0] = rxSignalReceived
;
541 debug
[1] = rxIsInFailsafeMode
;
542 debug
[2] = rxRuntimeConfig
.rcReadRawFn(&rxRuntimeConfig
, 0);
545 rxFlightChannelsValid
= true;
546 for (int channel
= 0; channel
< rxChannelCount
; channel
++) {
547 uint16_t sample
= rcRaw
[channel
];
549 const bool validPulse
= useValueFromRx
&& isPulseValid(sample
);
552 rcInvalidPulsPeriod
[channel
] = currentTimeMs
+ MAX_INVALID_PULS_TIME
;
554 if (cmp32(currentTimeMs
, rcInvalidPulsPeriod
[channel
]) < 0) {
555 continue; // skip to next channel to hold channel value MAX_INVALID_PULS_TIME
557 sample
= getRxfailValue(channel
); // after that apply rxfail value
558 if (channel
< NON_AUX_CHANNEL_COUNT
) {
559 rxFlightChannelsValid
= false;
563 if (feature(FEATURE_RX_PARALLEL_PWM
| FEATURE_RX_PPM
)) {
564 // smooth output for PWM and PPM
565 rcData
[channel
] = calculateChannelMovingAverage(channel
, sample
);
567 rcData
[channel
] = sample
;
571 if (rxFlightChannelsValid
&& !IS_RC_MODE_ACTIVE(BOXFAILSAFE
)) {
572 failsafeOnValidDataReceived();
574 rxIsInFailsafeMode
= true;
575 failsafeOnValidDataFailed();
576 for (int channel
= 0; channel
< rxChannelCount
; channel
++) {
577 rcData
[channel
] = getRxfailValue(channel
);
581 #ifdef DEBUG_RX_SIGNAL_LOSS
582 debug
[3] = rcData
[THROTTLE
];
586 bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs
)
588 if (auxiliaryProcessingRequired
) {
589 auxiliaryProcessingRequired
= !rxRuntimeConfig
.rcProcessFrameFn(&rxRuntimeConfig
);
592 if (!rxDataProcessingRequired
) {
596 rxDataProcessingRequired
= false;
597 rxNextUpdateAtUs
= currentTimeUs
+ DELAY_50_HZ
;
599 // only proceed when no more samples to skip and suspend period is over
601 if (currentTimeUs
> suspendRxSignalUntil
) {
608 readRxChannelsApplyRanges();
609 detectAndApplySignalLossBehaviour();
616 void parseRcChannels(const char *input
, rxConfig_t
*rxConfig
)
618 for (const char *c
= input
; *c
; c
++) {
619 const char *s
= strchr(rcChannelLetters
, *c
);
620 if (s
&& (s
< rcChannelLetters
+ RX_MAPPABLE_CHANNEL_COUNT
)) {
621 rxConfig
->rcmap
[s
- rcChannelLetters
] = c
- input
;
626 void setRssiFiltered(uint16_t newRssi
, rssiSource_e source
)
628 if (source
!= rssiSource
) {
635 #define RSSI_SAMPLE_COUNT 16
637 void setRssiUnfiltered(uint16_t rssiValue
, rssiSource_e source
)
639 if (source
!= rssiSource
) {
643 static uint16_t rssiSamples
[RSSI_SAMPLE_COUNT
];
644 static uint8_t rssiSampleIndex
= 0;
645 static unsigned sum
= 0;
647 sum
= sum
+ rssiValue
;
648 sum
= sum
- rssiSamples
[rssiSampleIndex
];
649 rssiSamples
[rssiSampleIndex
] = rssiValue
;
650 rssiSampleIndex
= (rssiSampleIndex
+ 1) % RSSI_SAMPLE_COUNT
;
652 int16_t rssiMean
= sum
/ RSSI_SAMPLE_COUNT
;
657 void setRssiMsp(uint8_t newMspRssi
)
659 if (rssiSource
== RSSI_SOURCE_NONE
) {
660 rssiSource
= RSSI_SOURCE_MSP
;
663 if (rssiSource
== RSSI_SOURCE_MSP
) {
664 rssi
= ((uint16_t)newMspRssi
) << 2;
665 lastMspRssiUpdateUs
= micros();
669 static void updateRSSIPWM(void)
671 // Read value of AUX channel as rssi
672 int16_t pwmRssi
= rcData
[rxConfig()->rssi_channel
- 1];
674 // RSSI_Invert option
675 if (rxConfig()->rssi_invert
) {
676 pwmRssi
= ((2000 - pwmRssi
) + 1000);
679 // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
680 setRssiFiltered(constrain((uint16_t)(((pwmRssi
- 1000) / 1000.0f
) * 1024.0f
), 0, RSSI_MAX_VALUE
), RSSI_SOURCE_RX_CHANNEL
);
683 static void updateRSSIADC(timeUs_t currentTimeUs
)
686 UNUSED(currentTimeUs
);
688 static uint32_t rssiUpdateAt
= 0;
690 if ((int32_t)(currentTimeUs
- rssiUpdateAt
) < 0) {
693 rssiUpdateAt
= currentTimeUs
+ DELAY_50_HZ
;
695 const uint16_t adcRssiSample
= adcGetChannel(ADC_RSSI
);
696 uint16_t rssiValue
= (uint16_t)((1024.0f
* adcRssiSample
) / (rxConfig()->rssi_scale
* 100.0f
));
697 rssiValue
= constrain(rssiValue
, 0, RSSI_MAX_VALUE
);
699 // RSSI_Invert option
700 if (rxConfig()->rssi_invert
) {
701 rssiValue
= RSSI_MAX_VALUE
- rssiValue
;
704 setRssiUnfiltered((uint16_t)rssiValue
, RSSI_SOURCE_ADC
);
708 void updateRSSI(timeUs_t currentTimeUs
)
710 switch (rssiSource
) {
711 case RSSI_SOURCE_RX_CHANNEL
:
714 case RSSI_SOURCE_ADC
:
715 updateRSSIADC(currentTimeUs
);
717 case RSSI_SOURCE_MSP
:
718 if (cmpTimeUs(micros(), lastMspRssiUpdateUs
) > MSP_RSSI_TIMEOUT_US
) {
727 uint16_t getRssi(void)
732 uint16_t rxGetRefreshRate(void)
734 return rxRuntimeConfig
.rxRefreshRate
;