AP_BoardConfig: split setup of safety switch init init_safety()

this allows it to be called late, so that servo outputs are fully
setup before the safety is disabled when BRD_SAFETYENABLE=0
This commit is contained in:
Andrew Tridgell 2017-04-30 10:47:27 +10:00
parent b1bd3f0364
commit 4c36c77db1
3 changed files with 12 additions and 6 deletions

View File

@ -213,3 +213,10 @@ void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask)
px4_setup_safety_mask(); px4_setup_safety_mask();
#endif #endif
} }
void AP_BoardConfig::init_safety()
{
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
px4_init_safety();
#endif
}

View File

@ -16,6 +16,7 @@ public:
}; };
void init(void); void init(void);
void init_safety(void);
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
@ -128,7 +129,7 @@ private:
void px4_drivers_start(void); void px4_drivers_start(void);
void px4_setup(void); void px4_setup(void);
void px4_setup_pwm(void); void px4_setup_pwm(void);
void px4_setup_safety(void); void px4_init_safety(void);
void px4_setup_safety_mask(void); void px4_setup_safety_mask(void);
void px4_setup_uart(void); void px4_setup_uart(void);
void px4_setup_sbus(void); void px4_setup_sbus(void);

View File

@ -145,12 +145,10 @@ void AP_BoardConfig::px4_setup_safety_mask()
} }
/* /*
setup safety switch init safety state
*/ */
void AP_BoardConfig::px4_setup_safety() void AP_BoardConfig::px4_init_safety()
{ {
px4_setup_safety_mask();
if (px4.safety_enable.get() == 0) { if (px4.safety_enable.get() == 0) {
hal.rcout->force_safety_off(); hal.rcout->force_safety_off();
hal.rcout->force_safety_no_wait(); hal.rcout->force_safety_no_wait();
@ -533,7 +531,7 @@ void AP_BoardConfig::px4_setup()
{ {
px4_setup_peripherals(); px4_setup_peripherals();
px4_setup_pwm(); px4_setup_pwm();
px4_setup_safety(); px4_setup_safety_mask();
px4_setup_uart(); px4_setup_uart();
px4_setup_sbus(); px4_setup_sbus();
px4_setup_drivers(); px4_setup_drivers();