AP_AHRS: convert APM_BUILD_COPTER_OR_HELI() to APM_BUILD_COPTER_OR_HELI

This commit is contained in:
Andy Piper 2021-10-25 18:08:59 +01:00 committed by Andrew Tridgell
parent 592241f029
commit e1dd0fd70d
2 changed files with 2 additions and 2 deletions

View File

@ -186,7 +186,7 @@ AP_AHRS::AP_AHRS(uint8_t flags) :
// load default values from var_info table
AP_Param::setup_object_defaults(this, var_info);
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduSub)
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub)
// Copter and Sub force the use of EKF
_ekf_flags |= AP_AHRS::FLAG_ALWAYS_USE_EKF;
#endif

View File

@ -633,7 +633,7 @@ Vector3f AP_AHRS_DCM::ra_delayed(uint8_t instance, const Vector3f &ra)
*/
bool AP_AHRS_DCM::should_correct_centrifugal() const
{
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)
return hal.util->get_soft_armed();
#endif