From 5b2d430a2a733a874fcdaf19ab00b8ca29b1e45f Mon Sep 17 00:00:00 2001 From: yaapu Date: Thu, 7 Jan 2021 09:13:07 +0100 Subject: [PATCH] AP_OpticalFlow: fix CXOF opflow driver, only apply yaw to flowRate as body rate comes from AHRS --- libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp index c2a82402c8..8ffb78fad5 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp @@ -186,8 +186,8 @@ void AP_OpticalFlow_CXOF::update(void) // copy average body rate to state structure state.bodyRate = Vector2f(gyro_sum.x / gyro_sum_count, gyro_sum.y / gyro_sum_count); + // we only apply yaw to flowRate as body rate comes from AHRS _applyYaw(state.flowRate); - _applyYaw(state.bodyRate); } else { // first frame received in some time so cannot calculate flow values state.flowRate.zero();