Plane: re-order channel initialisation

this fixes a problem with spurious throttle output during board
startup. Many thanks to Marco for finding this!
This commit is contained in:
Andrew Tridgell 2016-06-30 16:48:30 +10:00
parent 934d2b6ae4
commit ec367d4a09
3 changed files with 30 additions and 16 deletions

View File

@ -917,7 +917,8 @@ private:
bool setup_failsafe_mixing(void); bool setup_failsafe_mixing(void);
void set_control_channels(void); void set_control_channels(void);
void init_rc_in(); void init_rc_in();
void init_rc_out(); void init_rc_out_main();
void init_rc_out_aux();
void rudder_arm_disarm_check(); void rudder_arm_disarm_check();
void read_radio(); void read_radio();
void control_failsafe(uint16_t pwm); void control_failsafe(uint16_t pwm);

View File

@ -55,12 +55,14 @@ void Plane::init_rc_in()
} }
/* /*
initialise RC output channels initialise RC output for main channels. This is done early to allow
for BRD_SAFETYENABLE=0 and early servo control
*/ */
void Plane::init_rc_out() void Plane::init_rc_out_main()
{ {
channel_roll->enable_out(); // setup failsafe for bottom 4 channels. We don't do all channels
channel_pitch->enable_out(); // yet as some may be for VTOL motors in a quadplane
RC_Channel::setup_failsafe_trim_mask(0x000F);
/* /*
change throttle trim to minimum throttle. This prevents a change throttle trim to minimum throttle. This prevents a
@ -69,10 +71,26 @@ void Plane::init_rc_out()
*/ */
channel_throttle->set_radio_trim(throttle_min()); channel_throttle->set_radio_trim(throttle_min());
channel_roll->enable_out();
channel_pitch->enable_out();
if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) { if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) {
channel_throttle->enable_out(); channel_throttle->enable_out();
} }
channel_rudder->enable_out(); channel_rudder->enable_out();
// setup PX4 to output the min throttle when safety off if arming
// is setup for min on disarm
if (arming.arming_required() == AP_Arming::YES_MIN_PWM) {
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), throttle_min());
}
}
/*
initialise RC output channels for aux channels
*/
void Plane::init_rc_out_aux()
{
update_aux(); update_aux();
RC_Channel_aux::enable_aux_servos(); RC_Channel_aux::enable_aux_servos();
@ -81,12 +99,6 @@ void Plane::init_rc_out()
// setup PWM values to send if the FMU firmware dies // setup PWM values to send if the FMU firmware dies
RC_Channel::setup_failsafe_trim_all(); RC_Channel::setup_failsafe_trim_all();
// setup PX4 to output the min throttle when safety off if arming
// is setup for min on disarm
if (arming.arming_required() == AP_Arming::YES_MIN_PWM) {
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), throttle_min());
}
} }
/* /*

View File

@ -99,6 +99,9 @@ void Plane::init_ardupilot()
} }
#endif #endif
set_control_channels();
init_rc_out_main();
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// this must be before BoardConfig.init() so if // this must be before BoardConfig.init() so if
// BRD_SAFETYENABLE==0 then we don't have safety off yet // BRD_SAFETYENABLE==0 then we don't have safety off yet
@ -120,8 +123,6 @@ void Plane::init_ardupilot()
// allow servo set on all channels except first 4 // allow servo set on all channels except first 4
ServoRelayEvents.set_channel_mask(0xFFF0); ServoRelayEvents.set_channel_mask(0xFFF0);
set_control_channels();
// keep a record of how many resets have happened. This can be // keep a record of how many resets have happened. This can be
// used to detect in-flight resets // used to detect in-flight resets
g.num_resets.set_and_save(g.num_resets+1); g.num_resets.set_and_save(g.num_resets+1);
@ -230,9 +231,9 @@ void Plane::init_ardupilot()
startup_ground(); startup_ground();
// don't initialise rc output until after quadplane is setup as // don't initialise aux rc output until after quadplane is setup as
// that can change initial values of channels // that can change initial values of channels
init_rc_out(); init_rc_out_aux();
// choose the nav controller // choose the nav controller
set_nav_controller(); set_nav_controller();