Merge pull request #186 from priseborough/pr-ekfOutputPredictor

EKF: Improve Output Predictor Tracking
This commit is contained in:
Paul Riseborough 2016-10-04 07:47:34 +11:00 committed by GitHub
commit 5702c2d51b
5 changed files with 43 additions and 18 deletions

View File

@ -348,7 +348,7 @@ struct parameters {
ev_pos_body = {};
// output complementary filter tuning time constants
vel_Tau = 0.5f;
vel_Tau = 0.25f;
pos_Tau = 0.25f;
}

View File

@ -130,6 +130,8 @@ Ekf::Ekf():
_last_known_posNE.setZero();
_imu_down_sampled = {};
_q_down_sampled.setZero();
_vel_err_integ.setZero();
_pos_err_integ.setZero();
_mag_filt_state = {};
_delVel_sum = {};
_flow_gyro_bias = {};
@ -629,21 +631,24 @@ void Ekf::calculateOutputStates()
// that will cause the INS to track the EKF quaternions
_delta_angle_corr = delta_ang_error * att_gain;
// calculate a position correction that will be applied to the output state history
float pos_gain = _dt_ekf_avg / math::constrain(_params.pos_Tau, _dt_ekf_avg, 10.0f);
Vector3f pos_delta = (_state.pos - _output_sample_delayed.pos) * pos_gain;
// calculate velocity and position tracking errors
Vector3f vel_err = (_state.vel - _output_sample_delayed.vel);
Vector3f pos_err = (_state.pos - _output_sample_delayed.pos);
// collect magnitude tracking error for diagnostics
_output_tracking_error[0] = delta_ang_error.norm();
_output_tracking_error[1] = vel_err.norm();
_output_tracking_error[2] = pos_err.norm();
// calculate a velocity correction that will be applied to the output state history
Vector3f vel_delta;
if (_params.pos_Tau <= 0.0f) {
// this method will cause the velocity to be kinematically consistent with
// the position corretions rather than tracking the EKF states
vel_delta = pos_delta * (1.0f / time_delay);
} else {
// this method makes the velocity track the EKF states with the specified time constant
float vel_gain = _dt_ekf_avg / math::constrain(_params.vel_Tau, _dt_ekf_avg, 10.0f);
vel_delta = (_state.vel - _output_sample_delayed.vel) * vel_gain;
}
float vel_gain = _dt_ekf_avg / math::constrain(_params.vel_Tau, _dt_ekf_avg, 10.0f);
_vel_err_integ += vel_err;
Vector3f vel_correction = vel_err * vel_gain + _vel_err_integ * sq(vel_gain) * 0.1f;
// calculate a position correction that will be applied to the output state history
float pos_gain = _dt_ekf_avg / math::constrain(_params.pos_Tau, _dt_ekf_avg, 10.0f);
_pos_err_integ += pos_err;
Vector3f pos_correction = pos_err * pos_gain + _pos_err_integ * sq(pos_gain) * 0.1f;
// loop through the output filter state history and apply the corrections to the velocity and position states
// this method is too expensive to use for the attitude states due to the quaternion operations required
@ -655,10 +660,10 @@ void Ekf::calculateOutputStates()
output_states = _output_buffer.get_from_index(index);
// a constant velocity correction is applied
output_states.vel += vel_delta;
output_states.vel += vel_correction;
// a constant position correction is applied
output_states.pos += pos_delta;
output_states.pos += pos_correction;
// push the updated data to the buffer
_output_buffer.push_to_index(index,output_states);

View File

@ -117,6 +117,10 @@ public:
void get_pos_var(Vector3f &pos_var);
// return an array containing the output predictor angular, velocity and position tracking
// error magnitudes (rad), (m/s), (m)
void get_output_tracking_error(float error[3]);
// return true if the global position estimate is valid
bool global_position_is_valid();
@ -240,10 +244,13 @@ private:
float _mag_declination; // magnetic declination used by reset and fusion functions (rad)
// complementary filter states
// output predictor states
Vector3f _delta_angle_corr; // delta angle correction vector
imuSample _imu_down_sampled; // down sampled imu data (sensor rate -> filter update rate)
Quaternion _q_down_sampled; // down sampled quaternion (tracking delta angles between ekf update steps)
Vector3f _vel_err_integ; // integral of velocity tracking error
Vector3f _pos_err_integ; // integral of position tracking error
float _output_tracking_error[3];// contains the magnitude of the angle, velocity and position track errors (rad, m/s, m)
// variables used for the GPS quality checks
float _gpsDriftVelN; // GPS north position derivative (m/s)

View File

@ -674,6 +674,13 @@ void Ekf::get_ekf_origin(uint64_t *origin_time, map_projection_reference_s *orig
memcpy(origin_alt, &_gps_alt_ref, sizeof(float));
}
// return an array containing the output predictor angular, velocity and position tracking
// error magnitudes (rad), (m/s), (m)
void Ekf::get_output_tracking_error(float error[3])
{
memcpy(error, _output_tracking_error, 3 * sizeof(float));
}
// get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position
void Ekf::get_ekf_accuracy(float *ekf_eph, float *ekf_epv, bool *dead_reckoning)
{

View File

@ -88,8 +88,10 @@ public:
virtual void get_covariances(float *covariances) = 0;
// get the ekf WGS-84 origin position and height and the system time it was last set
// gets the variances for the NED velocity states
virtual void get_vel_var(Vector3f &vel_var) = 0;
// gets the variances for the NED position states
virtual void get_pos_var(Vector3f &pos_var) = 0;
// gets the innovation variance of the flow measurement
@ -104,6 +106,10 @@ public:
// gets the innovation of the HAGL measurement
virtual void get_hagl_innov(float *flow_innov_var) = 0;
// return an array containing the output predictor angular, velocity and position tracking
// error magnitudes (rad), (m/s), (m)
virtual void get_output_tracking_error(float error[3]) = 0;
// get the ekf WGS-84 origin positoin and height and the system time it was last set
virtual void get_ekf_origin(uint64_t *origin_time, map_projection_reference_s *origin_pos, float *origin_alt) = 0;