From 7bbbbd314c100ad5be04e49d565733145c70dbe2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 7 Nov 2020 09:30:31 +1100 Subject: [PATCH] AP_NavEKF3: added optflow support for AP_DAL --- libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index 82329ebb72..c2ad224598 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -172,6 +172,8 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam // this needs to be called externally. void NavEKF3_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset) { + AP::dal().writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset); + // limit update rate to maximum allowed by sensor buffers if ((imuSampleTime_ms - flowMeaTime_ms) < frontend->sensorIntervalMin_ms) { return;