Copter: consolidate setting of using-iterlock state

This commit is contained in:
Randy Mackay 2015-11-16 10:58:15 +09:00
parent 4192c3d0ad
commit 1b29a1af46
7 changed files with 15 additions and 21 deletions

View File

@ -114,11 +114,15 @@ void Copter::set_pre_arm_rc_check(bool b)
}
}
void Copter::set_using_interlock(bool b)
void Copter::update_using_interlock()
{
if(ap.using_interlock != b) {
ap.using_interlock = b;
}
#if FRAME_CONFIG == HELI_FRAME
// helicopters are always using motor interlock
ap.using_interlock = true;
#else
// check if we are using motor interlock control on an aux switch
ap.using_interlock = check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK);
#endif
}
void Copter::set_motor_emergency_stop(bool b)

View File

@ -480,16 +480,12 @@ void Copter::one_hz_loop()
// make it possible to change ahrs orientation at runtime during initial config
ahrs.set_orientation();
#if FRAME_CONFIG == HELI_FRAME
// helicopters are always using motor interlock
set_using_interlock(true);
#else
update_using_interlock();
#if FRAME_CONFIG != HELI_FRAME
// check the user hasn't updated the frame orientation
motors.set_frame_orientation(g.frame_orientation);
// check if we are using motor interlock control on an aux switch
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK));
// set all throttle channel settings
motors.set_throttle_range(g.throttle_min, channel_throttle->radio_min, channel_throttle->radio_max);
// set hover throttle

View File

@ -576,7 +576,7 @@ private:
void set_land_complete_maybe(bool b);
void set_pre_arm_check(bool b);
void set_pre_arm_rc_check(bool b);
void set_using_interlock(bool b);
void update_using_interlock();
void set_motor_emergency_stop(bool b);
float get_smoothing_gain();
void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);

View File

@ -16,9 +16,6 @@ static int8_t heli_dynamic_flight_counter;
// heli_init - perform any special initialisation required for the tradheli
void Copter::heli_init()
{
// helicopters are always using motor interlock
set_using_interlock(true);
/*
automatically set H_RSC_MIN and H_RSC_MAX from RC8_MIN and
RC8_MAX so that when users upgrade from tradheli version 3.3 to

View File

@ -231,7 +231,6 @@ bool Copter::pre_arm_checks(bool display_failure)
// if it is, switch needs to be in disabled position to arm
// otherwise exit immediately. This check to be repeated,
// as state can change at any time.
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK));
if (ap.using_interlock && motors.get_interlock()){
if (display_failure) {
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock Enabled");

View File

@ -244,14 +244,9 @@ void Copter::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
case AUXSW_RELAY:
case AUXSW_LANDING_GEAR:
case AUXSW_MOTOR_ESTOP:
do_aux_switch_function(ch_option, ch_flag);
break;
case AUXSW_MOTOR_INTERLOCK:
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK));
do_aux_switch_function(ch_option, ch_flag);
break;
}
}

View File

@ -162,6 +162,9 @@ void Copter::init_ardupilot()
log_init();
#endif
// update motor interlock state
update_using_interlock();
#if FRAME_CONFIG == HELI_FRAME
// trad heli specific initialisation
heli_init();