ArduCopter: be more consistent withb our defines around optional features

This commit is contained in:
Peter Barker 2024-01-04 17:02:47 +11:00 committed by Peter Barker
parent 35f1fdf0d8
commit 3691fdadc8
2 changed files with 4 additions and 2 deletions

View File

@ -398,10 +398,10 @@ bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
return filt_status.flags.attitude; return filt_status.flags.attitude;
} }
#if HAL_PROXIMITY_ENABLED
// check nothing is too close to vehicle // check nothing is too close to vehicle
bool AP_Arming_Copter::proximity_checks(bool display_failure) const bool AP_Arming_Copter::proximity_checks(bool display_failure) const
{ {
#if HAL_PROXIMITY_ENABLED
if (!AP_Arming::proximity_checks(display_failure)) { if (!AP_Arming::proximity_checks(display_failure)) {
return false; return false;
@ -425,9 +425,9 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
} }
#endif #endif
#endif
return true; return true;
} }
#endif // HAL_PROXIMITY_ENABLED
// performs mandatory gps checks. returns true if passed // performs mandatory gps checks. returns true if passed
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)

View File

@ -27,7 +27,9 @@ protected:
bool pre_arm_checks(bool display_failure) override; bool pre_arm_checks(bool display_failure) override;
bool pre_arm_ekf_attitude_check(); bool pre_arm_ekf_attitude_check();
#if HAL_PROXIMITY_ENABLED
bool proximity_checks(bool display_failure) const override; bool proximity_checks(bool display_failure) const override;
#endif
bool arm_checks(AP_Arming::Method method) override; 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 // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced