mirror of https://github.com/ArduPilot/ardupilot
Plane: try to load px4 mixer 10 times on boot
this allows for possible temporary failures
This commit is contained in:
parent
3e74b82bc4
commit
47f4a5db10
|
@ -761,7 +761,8 @@ private:
|
|||
void update_cruise();
|
||||
void update_fbwb_speed_height(void);
|
||||
void setup_turn_angle(void);
|
||||
bool create_mixer_file(const char *filename);
|
||||
bool print_buffer(char *&buf, uint16_t &buf_size, const char *fmt, ...);
|
||||
bool create_mixer(char *buf, uint16_t buf_size, const char *filename);
|
||||
bool setup_failsafe_mixing(void);
|
||||
void set_control_channels(void);
|
||||
void init_rc_in();
|
||||
|
|
|
@ -105,7 +105,12 @@ void Plane::init_ardupilot()
|
|||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
// this must be before BoardConfig.init() so if
|
||||
// BRD_SAFETYENABLE==0 then we don't have safety off yet
|
||||
setup_failsafe_mixing();
|
||||
for (uint8_t tries=0; tries<10; tries++) {
|
||||
if (setup_failsafe_mixing()) {
|
||||
break;
|
||||
}
|
||||
hal.scheduler->delay(10);
|
||||
}
|
||||
#endif
|
||||
|
||||
BoardConfig.init();
|
||||
|
|
Loading…
Reference in New Issue