flow_fusion: corrected sign of gyro data when it is taken from the ekf

gyro data

Signed-off-by: Roman <bapstroman@gmail.com>
This commit is contained in:
Roman 2018-06-13 21:52:42 +02:00
parent c6ed2ccfcd
commit c8af315aa7

View File

@ -564,7 +564,8 @@ bool Ekf::calcOptFlowBodyRateComp()
} else {
// Use the EKF gyro data if optical flow sensor gyro data is not available
_flow_sample_delayed.gyroXYZ = _imu_del_ang_of;
// for clarification of the sign see definition of flowSample and imuSample in common.h
_flow_sample_delayed.gyroXYZ = - _imu_del_ang_of;
_flow_gyro_bias.zero();
}