mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Merge remote-tracking branch 'prodrone/improved_rx_failsafe_detection' into betaflight
Conflicts: src/main/drivers/accgyro_mpu6500.c src/main/drivers/accgyro_spi_mpu6000.c src/main/drivers/system.c src/main/mw.c src/main/rx/rx.c src/main/sensors/initialisation.c
This commit is contained in:
commit
cb7028b7f1
4 changed files with 55 additions and 16 deletions
|
@ -113,7 +113,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 displayInit(rxConfig_t *intialRxConfig);
|
||||
|
@ -407,7 +407,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