Copter: Add GCS failsafe pre-arm check
This commit is contained in:
parent
83e05303be
commit
9cc192f36c
@ -56,7 +56,8 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
|
|||||||
& parameter_checks(display_failure)
|
& parameter_checks(display_failure)
|
||||||
& motor_checks(display_failure)
|
& motor_checks(display_failure)
|
||||||
& pilot_throttle_checks(display_failure)
|
& pilot_throttle_checks(display_failure)
|
||||||
& oa_checks(display_failure) &
|
& oa_checks(display_failure)
|
||||||
|
& gcs_failsafe_check(display_failure) &
|
||||||
AP_Arming::pre_arm_checks(display_failure);
|
AP_Arming::pre_arm_checks(display_failure);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -525,6 +526,15 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Check GCS failsafe
|
||||||
|
bool AP_Arming_Copter::gcs_failsafe_check(bool display_failure)
|
||||||
|
{
|
||||||
|
if (copter.failsafe.gcs) {
|
||||||
|
check_failed(display_failure, "GCS failsafe on");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// arm_checks - perform final checks before arming
|
// arm_checks - perform final checks before arming
|
||||||
// always called just before arming. Return true if ok to arm
|
// always called just before arming. Return true if ok to arm
|
||||||
|
@ -50,6 +50,7 @@ protected:
|
|||||||
bool pilot_throttle_checks(bool display_failure);
|
bool pilot_throttle_checks(bool display_failure);
|
||||||
bool oa_checks(bool display_failure);
|
bool oa_checks(bool display_failure);
|
||||||
bool mandatory_gps_checks(bool display_failure);
|
bool mandatory_gps_checks(bool display_failure);
|
||||||
|
bool gcs_failsafe_check(bool display_failure);
|
||||||
|
|
||||||
void set_pre_arm_check(bool b);
|
void set_pre_arm_check(bool b);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user