mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: 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:
parent
3c9c4a58b8
commit
709656c49d
|
@ -303,9 +303,9 @@ bool AP_Arming::barometer_checks(bool report)
|
|||
return true;
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
bool AP_Arming::airspeed_checks(bool report)
|
||||
{
|
||||
#if AP_AIRSPEED_ENABLED
|
||||
if (check_enabled(ARMING_CHECK_AIRSPEED)) {
|
||||
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
||||
if (airspeed == nullptr) {
|
||||
|
@ -319,10 +319,10 @@ bool AP_Arming::airspeed_checks(bool report)
|
|||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif // AP_AIRSPEED_ENABLED
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
bool AP_Arming::logging_checks(bool report)
|
||||
|
@ -1199,8 +1199,6 @@ bool AP_Arming::proximity_checks(bool report) const
|
|||
return false;
|
||||
}
|
||||
return true;
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
||||
|
|
|
@ -236,8 +236,6 @@ protected:
|
|||
|
||||
bool fettec_checks(bool display_failure) const;
|
||||
|
||||
bool kdecan_checks(bool display_failure) const;
|
||||
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
virtual bool proximity_checks(bool report) const;
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue