Copter: move Disarm/EStop/Interlock check from arm_checks to run_pre_arm_checks
This commit is contained in:
parent
073683cc69
commit
a4d3607de1
@ -46,10 +46,20 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
|
||||
|
||||
// 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.
|
||||
// otherwise exit immediately.
|
||||
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
|
||||
check_failed(display_failure, "Motor Interlock Enabled");
|
||||
return false;
|
||||
}
|
||||
|
||||
// if we are using motor Estop switch, it must not be in Estop position
|
||||
if (SRV_Channels::get_emergency_stop()){
|
||||
check_failed(display_failure, "Motor Emergency Stopped");
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!disarm_switch_checks(display_failure)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// if pre arm checks are disabled run only the mandatory checks
|
||||
@ -636,19 +646,6 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
||||
return false;
|
||||
}
|
||||
|
||||
// if we are using motor interlock switch and it's enabled, fail to arm
|
||||
// skip check in Throw mode which takes control of the motor interlock
|
||||
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
|
||||
check_failed(true, "Motor Interlock Enabled");
|
||||
return false;
|
||||
}
|
||||
|
||||
// if we are using motor Estop switch, it must not be in Estop position
|
||||
if (SRV_Channels::get_emergency_stop()){
|
||||
check_failed(true, "Motor Emergency Stopped");
|
||||
return false;
|
||||
}
|
||||
|
||||
// succeed if arming checks are disabled
|
||||
if (checks_to_perform == 0) {
|
||||
return true;
|
||||
|
Loading…
Reference in New Issue
Block a user