AP_OpticalFlow: fix CXOF opflow driver, only apply yaw to flowRate as body rate comes from AHRS

This commit is contained in:
yaapu 2021-01-07 09:13:07 +01:00 committed by Andrew Tridgell
parent 8728148db6
commit 5b2d430a2a
1 changed files with 1 additions and 1 deletions

View File

@ -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();