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/>.
25 #include "build_config.h"
28 #include "common/maths.h"
30 #include "config/parameter_group.h"
31 #include "config/parameter_group_ids.h"
33 #include "config/config.h"
34 #include "config/feature.h"
35 #include "config/config_reset.h"
37 #include "drivers/serial.h"
38 #include "drivers/adc.h"
40 #include "io/serial.h"
41 #include "io/rc_controls.h"
43 #include "flight/failsafe.h"
45 #include "drivers/gpio.h"
46 #include "drivers/timer.h"
47 #include "drivers/pwm_rx.h"
48 #include "drivers/system.h"
52 #include "rx/spektrum.h"
61 //#define DEBUG_RX_SIGNAL_LOSS
63 const char rcChannelLetters
[] = "AERT12345678abcdefgh";
65 uint16_t rssi
= 0; // range: [0;1023]
67 static bool rxDataReceived
= false;
68 static bool rxSignalReceived
= false;
69 static bool rxSignalReceivedNotDataDriven
= false;
70 static bool rxFlightChannelsValid
= false;
71 static bool rxIsInFailsafeMode
= true;
72 static bool rxIsInFailsafeModeNotDataDriven
= true;
74 static uint32_t rxUpdateAt
= 0;
75 static uint32_t needRxSignalBefore
= 0;
76 static uint32_t suspendRxSignalUntil
= 0;
77 static uint8_t skipRxSamples
= 0;
79 int16_t rcRaw
[MAX_SUPPORTED_RC_CHANNEL_COUNT
]; // interval [1000;2000]
80 int16_t rcData
[MAX_SUPPORTED_RC_CHANNEL_COUNT
]; // interval [1000;2000]
81 uint32_t rcInvalidPulsPeriod
[MAX_SUPPORTED_RC_CHANNEL_COUNT
];
83 #define MAX_INVALID_PULS_TIME 300
84 #define PPM_AND_PWM_SAMPLE_COUNT 3
86 #define DELAY_50_HZ (1000000 / 50)
87 #define DELAY_10_HZ (1000000 / 10)
88 #define DELAY_5_HZ (1000000 / 5)
89 #define SKIP_RC_ON_SUSPEND_PERIOD 1500000 // 1.5 second period in usec (call frequency independent)
90 #define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent)
92 static uint8_t rcSampleIndex
= 0;
94 rxRuntimeConfig_t rxRuntimeConfig
;
96 PG_REGISTER_WITH_RESET(rxConfig_t
, rxConfig
, PG_RX_CONFIG
, 0);
98 PG_REGISTER_ARR_WITH_RESET(rxFailsafeChannelConfig_t
, MAX_SUPPORTED_RC_CHANNEL_COUNT
, failsafeChannelConfigs
, PG_FAILSAFE_CHANNEL_CONFIG
, 0);
99 PG_REGISTER_ARR_WITH_RESET(rxChannelRangeConfiguration_t
, NON_AUX_CHANNEL_COUNT
, channelRanges
, PG_CHANNEL_RANGE_CONFIG
, 0);
101 void pgReset_rxConfig(rxConfig_t
*instance
)
103 RESET_CONFIG(rxConfig_t
, instance
,
108 .rx_min_usec
= 885, // any of first 4 channels below this value will trigger rx loss detection
109 .rx_max_usec
= 2115, // any of first 4 channels above this value will trigger rx loss detection
110 .rssi_scale
= RSSI_SCALE_DEFAULT
,
114 void pgReset_channelRanges(rxChannelRangeConfiguration_t
*instance
) {
115 // set default calibration to full range and 1:1 mapping
116 for (int i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
117 instance
->min
= PWM_RANGE_MIN
;
118 instance
->max
= PWM_RANGE_MAX
;
123 void pgReset_failsafeChannelConfigs(rxFailsafeChannelConfig_t
*instance
)
125 for (int i
= 0; i
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; i
++) {
126 instance
->mode
= (i
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_MODE_AUTO
: RX_FAILSAFE_MODE_HOLD
;
127 instance
->step
= (i
== THROTTLE
) ? CHANNEL_VALUE_TO_RXFAIL_STEP(rxConfig()->rx_min_usec
) : CHANNEL_VALUE_TO_RXFAIL_STEP(rxConfig()->midrc
);
133 static uint16_t nullReadRawRC(rxRuntimeConfig_t
*rxRuntimeConfig
, uint8_t channel
) {
134 UNUSED(rxRuntimeConfig
);
137 return PPM_RCVR_TIMEOUT
;
140 static rcReadRawDataPtr rcReadRawFunc
= nullReadRawRC
;
141 static uint16_t rxRefreshRate
;
143 void serialRxInit(rxConfig_t
*rxConfig
);
145 #define REQUIRED_CHANNEL_MASK 0x0F // first 4 channels
147 static uint8_t validFlightChannelMask
;
149 STATIC_UNIT_TESTED
void rxResetFlightChannelStatus(void) {
150 validFlightChannelMask
= REQUIRED_CHANNEL_MASK
;
153 STATIC_UNIT_TESTED
bool rxHaveValidFlightChannels(void)
155 return (validFlightChannelMask
== REQUIRED_CHANNEL_MASK
);
158 STATIC_UNIT_TESTED
bool isPulseValid(uint16_t pulseDuration
)
160 return pulseDuration
>= rxConfig()->rx_min_usec
&&
161 pulseDuration
<= rxConfig()->rx_max_usec
;
164 // pulse duration is in micro seconds (usec)
165 STATIC_UNIT_TESTED
void rxUpdateFlightChannelStatus(uint8_t channel
, bool valid
)
167 if (channel
< NON_AUX_CHANNEL_COUNT
&& !valid
) {
168 // if signal is invalid - mark channel as BAD
169 validFlightChannelMask
&= ~(1 << channel
);
173 void rxInit(modeActivationCondition_t
*modeActivationConditions
)
180 for (i
= 0; i
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; i
++) {
181 rcData
[i
] = rxConfig()->midrc
;
182 rcInvalidPulsPeriod
[i
] = millis() + MAX_INVALID_PULS_TIME
;
185 rcData
[THROTTLE
] = (feature(FEATURE_3D
)) ? rxConfig()->midrc
: rxConfig()->rx_min_usec
;
187 // Initialize ARM switch to OFF position when arming via switch is defined
188 for (i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
189 modeActivationCondition_t
*modeActivationCondition
= &modeActivationConditions
[i
];
190 if (modeActivationCondition
->modeId
== BOXARM
&& IS_RANGE_USABLE(&modeActivationCondition
->range
)) {
191 // ARM switch is defined, determine an OFF value
192 if (modeActivationCondition
->range
.startStep
> 0) {
193 value
= MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition
->range
.startStep
- 1));
195 value
= MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition
->range
.endStep
+ 1));
197 // Initialize ARM AUX channel to OFF value
198 rcData
[modeActivationCondition
->auxChannelIndex
+ NON_AUX_CHANNEL_COUNT
] = value
;
203 if (feature(FEATURE_RX_SERIAL
)) {
204 serialRxInit(rxConfig());
208 if (feature(FEATURE_RX_MSP
)) {
209 rxMspInit(&rxRuntimeConfig
, &rcReadRawFunc
);
212 if (feature(FEATURE_RX_PPM
) || feature(FEATURE_RX_PARALLEL_PWM
)) {
213 rxRefreshRate
= 20000;
214 rxPwmInit(&rxRuntimeConfig
, &rcReadRawFunc
);
219 void serialRxInit(rxConfig_t
*rxConfig
)
221 bool enabled
= false;
222 switch (rxConfig
->serialrx_provider
) {
223 case SERIALRX_SPEKTRUM1024
:
224 rxRefreshRate
= 22000;
225 enabled
= spektrumInit(&rxRuntimeConfig
, &rcReadRawFunc
);
227 case SERIALRX_SPEKTRUM2048
:
228 rxRefreshRate
= 11000;
229 enabled
= spektrumInit(&rxRuntimeConfig
, &rcReadRawFunc
);
232 rxRefreshRate
= 11000;
233 enabled
= sbusInit(&rxRuntimeConfig
, &rcReadRawFunc
);
236 rxRefreshRate
= 11000;
237 enabled
= sumdInit(&rxRuntimeConfig
, &rcReadRawFunc
);
240 rxRefreshRate
= 11000;
241 enabled
= sumhInit(&rxRuntimeConfig
, &rcReadRawFunc
);
243 case SERIALRX_XBUS_MODE_B
:
244 case SERIALRX_XBUS_MODE_B_RJ01
:
245 rxRefreshRate
= 11000;
246 enabled
= xBusInit(&rxRuntimeConfig
, &rcReadRawFunc
);
249 enabled
= ibusInit(&rxRuntimeConfig
, &rcReadRawFunc
);
254 featureClear(FEATURE_RX_SERIAL
);
255 rcReadRawFunc
= nullReadRawRC
;
259 uint8_t serialRxFrameStatus(void)
262 * FIXME: Each of the xxxxFrameStatus() methods MUST be able to survive being called without the
263 * corresponding xxxInit() method having been called first.
265 * This situation arises when the cli or the msp changes the value of rxConfig->serialrx_provider
267 * A solution is for the ___Init() to configure the serialRxFrameStatus function pointer which
268 * should be used instead of the switch statement below.
270 switch (rxConfig()->serialrx_provider
) {
271 case SERIALRX_SPEKTRUM1024
:
272 case SERIALRX_SPEKTRUM2048
:
273 return spektrumFrameStatus();
275 return sbusFrameStatus();
277 return sumdFrameStatus();
279 return sumhFrameStatus();
280 case SERIALRX_XBUS_MODE_B
:
281 case SERIALRX_XBUS_MODE_B_RJ01
:
282 return xBusFrameStatus();
284 return ibusFrameStatus();
286 return SERIAL_RX_FRAME_PENDING
;
290 uint8_t calculateChannelRemapping(uint8_t *channelMap
, uint8_t channelMapEntryCount
, uint8_t channelToRemap
)
292 if (channelToRemap
< channelMapEntryCount
) {
293 return channelMap
[channelToRemap
];
295 return channelToRemap
;
298 bool rxIsReceivingSignal(void)
300 return rxSignalReceived
;
303 bool rxAreFlightChannelsValid(void)
305 return rxFlightChannelsValid
;
307 static bool isRxDataDriven(void) {
308 return !(feature(FEATURE_RX_PARALLEL_PWM
| FEATURE_RX_PPM
));
311 static void resetRxSignalReceivedFlagIfNeeded(uint32_t currentTime
)
313 if (!rxSignalReceived
) {
317 if (((int32_t)(currentTime
- needRxSignalBefore
) >= 0)) {
318 rxSignalReceived
= false;
319 rxSignalReceivedNotDataDriven
= false;
323 void suspendRxSignal(void)
325 suspendRxSignalUntil
= micros() + SKIP_RC_ON_SUSPEND_PERIOD
;
326 skipRxSamples
= SKIP_RC_SAMPLES_ON_RESUME
;
327 failsafeOnRxSuspend(SKIP_RC_ON_SUSPEND_PERIOD
);
330 void resumeRxSignal(void)
332 suspendRxSignalUntil
= micros();
333 skipRxSamples
= SKIP_RC_SAMPLES_ON_RESUME
;
334 failsafeOnRxResume();
337 void updateRx(uint32_t currentTime
)
339 resetRxSignalReceivedFlagIfNeeded(currentTime
);
341 if (isRxDataDriven()) {
342 rxDataReceived
= false;
347 if (feature(FEATURE_RX_SERIAL
)) {
348 uint8_t frameStatus
= serialRxFrameStatus();
350 if (frameStatus
& SERIAL_RX_FRAME_COMPLETE
) {
351 rxDataReceived
= true;
352 rxIsInFailsafeMode
= (frameStatus
& SERIAL_RX_FRAME_FAILSAFE
) != 0;
353 rxSignalReceived
= !rxIsInFailsafeMode
;
354 needRxSignalBefore
= currentTime
+ DELAY_10_HZ
;
359 if (feature(FEATURE_RX_MSP
)) {
360 rxDataReceived
= rxMspFrameComplete();
362 if (rxDataReceived
) {
363 rxSignalReceived
= true;
364 rxIsInFailsafeMode
= false;
365 needRxSignalBefore
= currentTime
+ DELAY_5_HZ
;
369 if (feature(FEATURE_RX_PPM
)) {
370 if (isPPMDataBeingReceived()) {
371 rxSignalReceivedNotDataDriven
= true;
372 rxIsInFailsafeModeNotDataDriven
= false;
373 needRxSignalBefore
= currentTime
+ DELAY_10_HZ
;
374 resetPPMDataReceivedState();
378 if (feature(FEATURE_RX_PARALLEL_PWM
)) {
379 if (isPWMDataBeingReceived()) {
380 rxSignalReceivedNotDataDriven
= true;
381 rxIsInFailsafeModeNotDataDriven
= false;
382 needRxSignalBefore
= currentTime
+ DELAY_10_HZ
;
388 bool shouldProcessRx(uint32_t currentTime
)
390 return rxDataReceived
|| ((int32_t)(currentTime
- rxUpdateAt
) >= 0); // data driven or 50Hz
393 static uint16_t calculateNonDataDrivenChannel(uint8_t chan
, uint16_t sample
)
395 static uint16_t rcSamples
[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT
][PPM_AND_PWM_SAMPLE_COUNT
];
396 static bool rxSamplesCollected
= false;
398 uint8_t currentSampleIndex
= rcSampleIndex
% PPM_AND_PWM_SAMPLE_COUNT
;
400 // update the recent samples and compute the average of them
401 rcSamples
[chan
][currentSampleIndex
] = sample
;
403 // avoid returning an incorrect average which would otherwise occur before enough samples
404 if (!rxSamplesCollected
) {
405 if (rcSampleIndex
< PPM_AND_PWM_SAMPLE_COUNT
) {
408 rxSamplesCollected
= true;
411 uint16_t rcDataMean
= 0;
413 for (sampleIndex
= 0; sampleIndex
< PPM_AND_PWM_SAMPLE_COUNT
; sampleIndex
++)
414 rcDataMean
+= rcSamples
[chan
][sampleIndex
];
416 return rcDataMean
/ PPM_AND_PWM_SAMPLE_COUNT
;
419 static uint16_t getRxfailValue(uint8_t channel
)
421 rxFailsafeChannelConfig_t
*failsafeChannelConfig
= failsafeChannelConfigs(channel
);
422 uint8_t mode
= failsafeChannelConfig
->mode
;
424 // force auto mode to prevent fly away when failsafe stage 2 is disabled
425 if ( channel
< NON_AUX_CHANNEL_COUNT
&& (!feature(FEATURE_FAILSAFE
)) ) {
426 mode
= RX_FAILSAFE_MODE_AUTO
;
430 case RX_FAILSAFE_MODE_AUTO
:
435 return rxConfig()->midrc
;
438 if (feature(FEATURE_3D
))
439 return rxConfig()->midrc
;
441 return rxConfig()->rx_min_usec
;
446 case RX_FAILSAFE_MODE_INVALID
:
447 case RX_FAILSAFE_MODE_HOLD
:
448 return rcData
[channel
];
450 case RX_FAILSAFE_MODE_SET
:
451 return RXFAIL_STEP_TO_CHANNEL_VALUE(failsafeChannelConfig
->step
);
455 STATIC_UNIT_TESTED
uint16_t applyRxChannelRangeConfiguraton(int sample
, rxChannelRangeConfiguration_t
*range
)
457 // Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT
458 if (sample
== PPM_RCVR_TIMEOUT
) {
459 return PPM_RCVR_TIMEOUT
;
462 sample
= scaleRange(sample
, range
->min
, range
->max
, PWM_RANGE_MIN
, PWM_RANGE_MAX
);
463 sample
= MIN(MAX(PWM_PULSE_MIN
, sample
), PWM_PULSE_MAX
);
468 static void readRxChannelsApplyRanges(void)
472 for (channel
= 0; channel
< rxRuntimeConfig
.channelCount
; channel
++) {
474 uint8_t rawChannel
= calculateChannelRemapping(rxConfig()->rcmap
, REMAPPABLE_CHANNEL_COUNT
, channel
);
476 // sample the channel
477 uint16_t sample
= rcReadRawFunc(&rxRuntimeConfig
, rawChannel
);
479 // apply the rx calibration
480 if (channel
< NON_AUX_CHANNEL_COUNT
) {
481 sample
= applyRxChannelRangeConfiguraton(sample
, channelRanges(channel
));
484 rcRaw
[channel
] = sample
;
488 static void detectAndApplySignalLossBehaviour(void)
492 bool useValueFromRx
= true;
493 bool rxIsDataDriven
= isRxDataDriven();
494 uint32_t currentMilliTime
= millis();
496 if (!rxIsDataDriven
) {
497 rxSignalReceived
= rxSignalReceivedNotDataDriven
;
498 rxIsInFailsafeMode
= rxIsInFailsafeModeNotDataDriven
;
501 if (!rxSignalReceived
|| rxIsInFailsafeMode
) {
502 useValueFromRx
= false;
505 #ifdef DEBUG_RX_SIGNAL_LOSS
506 debug
[0] = rxSignalReceived
;
507 debug
[1] = rxIsInFailsafeMode
;
508 debug
[2] = rcReadRawFunc(&rxRuntimeConfig
, 0);
511 rxResetFlightChannelStatus();
513 for (channel
= 0; channel
< rxRuntimeConfig
.channelCount
; channel
++) {
515 sample
= (useValueFromRx
) ? rcRaw
[channel
] : PPM_RCVR_TIMEOUT
;
517 bool validPulse
= isPulseValid(sample
);
520 if (currentMilliTime
< rcInvalidPulsPeriod
[channel
]) {
521 sample
= rcData
[channel
]; // hold channel for MAX_INVALID_PULS_TIME
523 sample
= getRxfailValue(channel
); // after that apply rxfail value
524 rxUpdateFlightChannelStatus(channel
, validPulse
);
527 rcInvalidPulsPeriod
[channel
] = currentMilliTime
+ MAX_INVALID_PULS_TIME
;
530 if (rxIsDataDriven
) {
531 rcData
[channel
] = sample
;
533 rcData
[channel
] = calculateNonDataDrivenChannel(channel
, sample
);
537 rxFlightChannelsValid
= rxHaveValidFlightChannels();
539 if ((rxFlightChannelsValid
) && !(IS_RC_MODE_ACTIVE(BOXFAILSAFE
) && feature(FEATURE_FAILSAFE
))) {
540 failsafeOnValidDataReceived();
542 rxIsInFailsafeMode
= rxIsInFailsafeModeNotDataDriven
= true;
543 failsafeOnValidDataFailed();
545 for (channel
= 0; channel
< rxRuntimeConfig
.channelCount
; channel
++) {
546 rcData
[channel
] = getRxfailValue(channel
);
550 #ifdef DEBUG_RX_SIGNAL_LOSS
551 debug
[3] = rcData
[THROTTLE
];
555 void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime
)
557 rxUpdateAt
= currentTime
+ DELAY_50_HZ
;
559 // only proceed when no more samples to skip and suspend period is over
561 if (currentTime
> suspendRxSignalUntil
) {
567 readRxChannelsApplyRanges();
568 detectAndApplySignalLossBehaviour();
573 void parseRcChannels(const char *input
, rxConfig_t
*rxConfig
)
577 for (c
= input
; *c
; c
++) {
578 s
= strchr(rcChannelLetters
, *c
);
579 if (s
&& (s
< rcChannelLetters
+ MAX_MAPPABLE_RX_INPUTS
))
580 rxConfig
->rcmap
[s
- rcChannelLetters
] = c
- input
;
584 void updateRSSIPWM(void)
587 // Read value of AUX channel as rssi
588 pwmRssi
= rcData
[rxConfig()->rssi_channel
- 1];
590 // RSSI_Invert option
591 if (rxConfig()->rssi_ppm_invert
) {
592 pwmRssi
= ((2000 - pwmRssi
) + 1000);
595 // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
596 rssi
= (uint16_t)((constrain(pwmRssi
- 1000, 0, 1000) / 1000.0f
) * 1023.0f
);
599 #define RSSI_ADC_SAMPLE_COUNT 16
600 //#define RSSI_SCALE (0xFFF / 100.0f)
602 void updateRSSIADC(uint32_t currentTime
)
607 static uint8_t adcRssiSamples
[RSSI_ADC_SAMPLE_COUNT
];
608 static uint8_t adcRssiSampleIndex
= 0;
609 static uint32_t rssiUpdateAt
= 0;
611 if ((int32_t)(currentTime
- rssiUpdateAt
) < 0) {
614 rssiUpdateAt
= currentTime
+ DELAY_50_HZ
;
616 int16_t adcRssiMean
= 0;
617 uint16_t adcRssiSample
= adcGetChannel(ADC_RSSI
);
618 uint8_t rssiPercentage
= adcRssiSample
/ rxConfig()->rssi_scale
;
620 adcRssiSampleIndex
= (adcRssiSampleIndex
+ 1) % RSSI_ADC_SAMPLE_COUNT
;
622 adcRssiSamples
[adcRssiSampleIndex
] = rssiPercentage
;
626 for (sampleIndex
= 0; sampleIndex
< RSSI_ADC_SAMPLE_COUNT
; sampleIndex
++) {
627 adcRssiMean
+= adcRssiSamples
[sampleIndex
];
630 adcRssiMean
= adcRssiMean
/ RSSI_ADC_SAMPLE_COUNT
;
632 rssi
= (uint16_t)((constrain(adcRssiMean
, 0, 100) / 100.0f
) * 1023.0f
);
636 void updateRSSI(uint32_t currentTime
)
639 if (rxConfig()->rssi_channel
> 0) {
641 } else if (feature(FEATURE_RSSI_ADC
)) {
642 updateRSSIADC(currentTime
);
646 void initRxRefreshRate(uint16_t *rxRefreshRatePtr
) {
647 *rxRefreshRatePtr
= rxRefreshRate
;