mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Improved RX failsafe detection & handling
modified debug output (currently disabled) To solve problem as indicated here: https://github.com/cleanflight/cleanflight/issues/1266#issuecomment-135640133 and here: https://github.com/cleanflight/cleanflight/pull/1340 and here: https://github.com/cleanflight/cleanflight/pull/1342 Tested on FrSKY X4RSB with latest CPPM firmware (non-EU version). Firmware filename: X4R-X4RSB_cppm_non-EU_150630 In both SBUS and CPPM mode. --- Added delay to rxfail detection All channels are monitored for bad (out of valid range) pulses. On bad pulses channel data will HOLD the last value for a period of MAX_INVALID_PULS_TIME (300ms) before starting rxfail substitution. This should prevent a too aggressive reaction to small dropouts. --- Init ARM switch rc channel to OFF for safety Initialize ARM switch to OFF position when arming via switch is defined. To prevent arming during init when RX is disconnected and/or when RX is connected but TX is still off. --- Modified rx_rx_unittest.cc Adapted because rxInit() parameters changed. Added tests for ARM switch initialization. No further tests added. --- Move smoothing of rcData to rcCommand Commit from @borisbstyle pr #1418 rc_smoothing function has changed to leave rcData unchanged in #1418
This commit is contained in:
parent
efc31f9d57
commit
a64e2c4f1a
4 changed files with 93 additions and 29 deletions
|
@ -112,7 +112,7 @@ void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers, servoMixe
|
|||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers);
|
||||
#endif
|
||||
void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfiguration);
|
||||
void rxInit(rxConfig_t *rxConfig);
|
||||
void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationConditions);
|
||||
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig);
|
||||
void navigationInit(gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
||||
void imuInit(void);
|
||||
|
@ -406,7 +406,7 @@ void init(void)
|
|||
|
||||
failsafeInit(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
||||
|
||||
rxInit(&masterConfig.rxConfig);
|
||||
rxInit(&masterConfig.rxConfig, currentProfile->modeActivationConditions);
|
||||
|
||||
#ifdef GPS
|
||||
if (feature(FEATURE_GPS)) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue