EKF: Fix bug in accumulation of IMU data for flow sensor gyro bias calculation

This commit is contained in:
Paul Riseborough
2017-09-14 15:47:15 +10:00
parent 3b3326e250
commit 1d3e8edc46
2 changed files with 6 additions and 6 deletions
+4
View File
@@ -379,6 +379,10 @@ void Ekf::controlOpticalFlowFusion()
}
}
// Accumulate autopilot gyro data across the same time interval as the flow sensor
_imu_del_ang_of += _imu_sample_delayed.delta_ang - _state.gyro_bias;
_delta_time_of += _imu_sample_delayed.delta_ang_dt;
// fuse the data
if (_control_status.flags.opt_flow) {
// Update optical flow bias estimates