ArduPlane: remove entire airspeed_checks if AP_AIRSPEED_ENABLED is off

saves bytes and removes some redundant code which is obscured when the ifdefs are inside the body
This commit is contained in:
Peter Barker 2024-01-09 17:30:56 +11:00 committed by Andrew Tridgell
parent 709656c49d
commit 0690e3c9fa

View File

@ -66,8 +66,10 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
// call parent class checks
bool ret = AP_Arming::pre_arm_checks(display_failure);
#if AP_AIRSPEED_ENABLED
// Check airspeed sensor
ret &= AP_Arming::airspeed_checks(display_failure);
#endif
if (plane.g.fs_timeout_long < plane.g.fs_timeout_short && plane.g.fs_action_short != FS_ACTION_SHORT_DISABLED) {
check_failed(display_failure, "FS_LONG_TIMEOUT < FS_SHORT_TIMEOUT");