diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index d2e4838f8c..72bc9addf0 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -398,10 +398,10 @@ bool AP_Arming_Copter::pre_arm_ekf_attitude_check() return filt_status.flags.attitude; } +#if HAL_PROXIMITY_ENABLED // check nothing is too close to vehicle bool AP_Arming_Copter::proximity_checks(bool display_failure) const { -#if HAL_PROXIMITY_ENABLED if (!AP_Arming::proximity_checks(display_failure)) { return false; @@ -425,9 +425,9 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const } #endif -#endif return true; } +#endif // HAL_PROXIMITY_ENABLED // performs mandatory gps checks. returns true if passed bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index 15495469b4..180525594c 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -27,7 +27,9 @@ protected: bool pre_arm_checks(bool display_failure) override; bool pre_arm_ekf_attitude_check(); +#if HAL_PROXIMITY_ENABLED bool proximity_checks(bool display_failure) const override; +#endif bool arm_checks(AP_Arming::Method method) override; // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced