diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 78da92bb96..1a039a2bf8 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -56,7 +56,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); } @@ -525,6 +526,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 diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index 824d0a8022..69962530d3 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -50,6 +50,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);