Copter: Add using_interlock flag, employ it in arming process

This commit is contained in:
Robert Lefebvre 2015-03-12 20:44:46 -04:00 committed by Randy Mackay
parent e4c5915330
commit 7d745587a4
3 changed files with 30 additions and 0 deletions

View File

@ -146,3 +146,10 @@ void set_motor_interlock(bool b)
}
}
void set_using_interlock(bool b)
{
if(ap.using_interlock != b) {
ap.using_interlock = b;
}
}

View File

@ -358,6 +358,7 @@ static union {
uint8_t gps_base_pos_set : 1; // 29 // true when the gps base position has been set (used for RTK gps only)
enum HomeState home_state : 2; // 30,31 // home status (unset, set, locked)
uint8_t motor_interlock : 1; // 32 // motor interlock status, final control for motors on/off
uint8_t using_interlock : 1; // 33 // aux switch motor interlock function is in use
};
uint32_t value;
} ap;

View File

@ -157,6 +157,16 @@ static bool init_arm_motors(bool arming_from_gcs)
did_ground_start = true;
}
// check if we are using motor interlock control on an aux switch
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK));
// if we are using motor interlock switch and it's disabled, fail to arm
if (ap.using_interlock && ap.motor_interlock){
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Motor Interlock Enabled"));
AP_Notify::flags.armed = false;
return false;
}
// enable gps velocity based centrefugal force compensation
ahrs.set_correct_centrifugal(true);
hal.util->set_soft_armed(true);
@ -206,6 +216,18 @@ static bool pre_arm_checks(bool display_failure)
return true;
}
// check if motor interlock aux switch is in use
// 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 && ap.motor_interlock){
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Motor Interlock Enabled"));
}
return false;
}
// exit immediately if we've already successfully performed the pre-arm check
if (ap.pre_arm_check) {
// run gps checks because results may change and affect LED colour