diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index c87382d5d3..8b1f4b3626 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -42,6 +42,7 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include #endif +#include #define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10) #define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20) @@ -2338,7 +2339,7 @@ void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &ra #if HAL_NAVEKF2_AVAILABLE EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride); #endif -#if HAL_NAVEKF3_AVAILABLE +#if EK3_FEATURE_OPTFLOW_FUSION EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset, heightOverride); #endif } @@ -2346,7 +2347,7 @@ void AP_AHRS::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &ra // retrieve latest corrected optical flow samples (used for calibration) bool AP_AHRS::getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const { -#if HAL_NAVEKF3_AVAILABLE +#if EK3_FEATURE_OPTFLOW_FUSION return EKF3.getOptFlowSample(timeStamp_ms, flowRate, bodyRate, losPred); #endif return false;