Skip to content

Commit

Permalink
AP_DAL: add and use pr/EK3_FEATURE_OPTFLOW_FUSION
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed May 9, 2023
1 parent 7ad8b90 commit 3b2cb9b
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion libraries/AP_DAL/AP_DAL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_WheelEncoder/AP_WheelEncoder.h>
#include <AP_NavEKF3/AP_NavEKF3_feature.h>

#if APM_BUILD_TYPE(APM_BUILD_Replay)
#include <AP_NavEKF2/AP_NavEKF2.h>
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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
}

/*
Expand Down

0 comments on commit 3b2cb9b

Please sign in to comment.