From 209e3641908e5943999d74b76f2ae1fc45e031cf Mon Sep 17 00:00:00 2001 From: priseborough Date: Wed, 12 Oct 2016 08:24:25 +1100 Subject: [PATCH] Copter: Add body position offset to optical flow interface --- ArduCopter/sensors.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index cc8e1bd2d4..f3579e9368 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -138,7 +138,8 @@ void Copter::update_optical_flow(void) uint8_t flowQuality = optflow.quality(); Vector2f flowRate = optflow.flowRate(); Vector2f bodyRate = optflow.bodyRate(); - ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update); + Vector3f posOffset = optflow.get_pos_offset(); + ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update, posOffset); if (g.log_bitmask & MASK_LOG_OPTFLOW) { Log_Write_Optflow(); }