diff --git a/EKF/control.cpp b/EKF/control.cpp index 75d6dd92fb..3cc36474cb 100644 --- a/EKF/control.cpp +++ b/EKF/control.cpp @@ -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 diff --git a/EKF/optflow_fusion.cpp b/EKF/optflow_fusion.cpp index 29ff1531fb..df0dd3163d 100644 --- a/EKF/optflow_fusion.cpp +++ b/EKF/optflow_fusion.cpp @@ -524,20 +524,16 @@ void Ekf::get_drag_innov_var(float drag_innov_var[2]) // calculate optical flow gyro bias errors void Ekf::calcOptFlowBias() { - // accumulate the bias corrected delta angles from the navigation sensor and lapsed time - _imu_del_ang_of += _imu_sample_delayed.delta_ang; - _delta_time_of += _imu_sample_delayed.delta_ang_dt; - // reset the accumulators if the time interval is too large if (_delta_time_of > 1.0f) { _imu_del_ang_of.setZero(); _delta_time_of = 0.0f; + return; } // if accumulation time differences are not excessive and accumulation time is adequate // compare the optical flow and and navigation rate data and calculate a bias error - if ((fabsf(_delta_time_of - _flow_sample_delayed.dt) < 0.05f) && (_delta_time_of > 0.01f) - && (_flow_sample_delayed.dt > 0.01f)) { + if ((fabsf(_delta_time_of - _flow_sample_delayed.dt) < 0.1f) && (_delta_time_of > 0.01f)) { // calculate a reference angular rate Vector3f reference_body_rate; reference_body_rate = _imu_del_ang_of * (1.0f / _delta_time_of);