Copter: Add GCS failsafe pre-arm check

This commit is contained in:
Matt Lawrence 2020-01-15 17:30:46 -05:00 committed by Randy Mackay
parent c7de86a241
commit d1feb93152
2 changed files with 12 additions and 1 deletions

View File

@ -60,7 +60,8 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
& parameter_checks(display_failure)
& motor_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);
}
@ -563,6 +564,15 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
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
// always called just before arming. Return true if ok to arm

View File

@ -49,6 +49,7 @@ protected:
bool pilot_throttle_checks(bool display_failure);
bool oa_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);