mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: add and use pr/EK3_FEATURE_OPTFLOW_FUSION
This commit is contained in:
parent
02c6784c11
commit
e9baf3d15a
|
@ -7,6 +7,7 @@
|
||||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||||
#include <AP_WheelEncoder/AP_WheelEncoder.h>
|
#include <AP_WheelEncoder/AP_WheelEncoder.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
|
#include <AP_NavEKF3/AP_NavEKF3_feature.h>
|
||||||
|
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||||
|
@ -467,7 +468,9 @@ void AP_DAL::handle_message(const log_ROFH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3)
|
||||||
{
|
{
|
||||||
_ROFH = msg;
|
_ROFH = msg;
|
||||||
ekf2.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride);
|
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);
|
ekf3.writeOptFlowMeas(msg.rawFlowQuality, msg.rawFlowRates, msg.rawGyroRates, msg.msecFlowMeas, msg.posOffset, msg.heightOverride);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue