diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 8e2b6fe87b7dab..561784de0f3fa9 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -6,6 +6,7 @@ #include #include #include +#include #if APM_BUILD_TYPE(APM_BUILD_Replay) #include @@ -66,7 +67,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) _RFRN.ahrs_airspeed_sensor_enabled = ahrs.airspeed_sensor_enabled(ahrs.get_active_airspeed_index()); _RFRN.available_memory = hal.util->available_memory(); _RFRN.ahrs_trim = ahrs.get_trim(); -#if AP_OPTICALFLOW_ENABLED +#if EK3_FEATURE_OPTFLOW_FUSION _RFRN.opticalflow_enabled = AP::opticalflow() && AP::opticalflow()->enabled(); #endif _RFRN.wheelencoder_enabled = AP::wheelencoder() && (AP::wheelencoder()->num_sensors() > 0); @@ -443,7 +444,9 @@ void AP_DAL::handle_message(const log_ROFH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _ROFH = msg; ekf2.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride); +#if EK3_FEATURE_OPTFLOW_FUSION ekf3.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride); +#endif } /*