|
|
@ -23,12 +23,6 @@ |
|
|
|
// from the GPS and wait for the ground speed to get above GPS_SPEED_MIN
|
|
|
|
// from the GPS and wait for the ground speed to get above GPS_SPEED_MIN
|
|
|
|
#define GPS_SPEED_RESET 100 |
|
|
|
#define GPS_SPEED_RESET 100 |
|
|
|
|
|
|
|
|
|
|
|
// the limit (in degrees/second) beyond which we stop integrating
|
|
|
|
|
|
|
|
// omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
|
|
|
|
|
|
|
|
// which results in false gyro drift. See
|
|
|
|
|
|
|
|
// http://gentlenav.googlecode.com/files/fastRotations.pdf
|
|
|
|
|
|
|
|
#define SPIN_RATE_LIMIT 20 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// table of user settable parameters
|
|
|
|
// table of user settable parameters
|
|
|
|
const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { |
|
|
|
const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { |
|
|
|
// @Param: YAW_P
|
|
|
|
// @Param: YAW_P
|
|
|
@ -76,13 +70,49 @@ AP_AHRS_DCM::update(void) |
|
|
|
void |
|
|
|
void |
|
|
|
AP_AHRS_DCM::matrix_update(float _G_Dt) |
|
|
|
AP_AHRS_DCM::matrix_update(float _G_Dt) |
|
|
|
{ |
|
|
|
{ |
|
|
|
// Equation 16, adding proportional and integral correction terms
|
|
|
|
// _omega_integ_corr is used for _centripetal correction
|
|
|
|
_omega = _gyro_vector + _omega_I + _omega_P + _omega_yaw_P; |
|
|
|
// (theoretically better than _omega)
|
|
|
|
|
|
|
|
_omega_integ_corr = _gyro_vector + _omega_I; |
|
|
|
|
|
|
|
|
|
|
|
_dcm_matrix.rotate(_omega * _G_Dt); |
|
|
|
// Equation 16, adding proportional and integral correction terms
|
|
|
|
|
|
|
|
_omega = _omega_integ_corr + _omega_P + _omega_yaw_P; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// this is a replacement of the DCM matrix multiply (equation
|
|
|
|
|
|
|
|
// 17), with known zero elements removed and the matrix
|
|
|
|
|
|
|
|
// operations inlined. This runs much faster than the original
|
|
|
|
|
|
|
|
// version of this code, as the compiler was doing a terrible
|
|
|
|
|
|
|
|
// job of realising that so many of the factors were in common
|
|
|
|
|
|
|
|
// or zero. It also uses much less stack, as we no longer need
|
|
|
|
|
|
|
|
// two additional local matrices
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Vector3f r = _omega * _G_Dt; |
|
|
|
|
|
|
|
_dcm_matrix.rotate(r); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// adjust an accelerometer vector for known acceleration forces
|
|
|
|
|
|
|
|
void |
|
|
|
|
|
|
|
AP_AHRS_DCM::accel_adjust(Vector3f &accel) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
float veloc; |
|
|
|
|
|
|
|
// compensate for linear acceleration. This makes a
|
|
|
|
|
|
|
|
// surprisingly large difference in the pitch estimate when
|
|
|
|
|
|
|
|
// turning, plus on takeoff and landing
|
|
|
|
|
|
|
|
float acceleration = _gps->acceleration(); |
|
|
|
|
|
|
|
accel.x -= acceleration; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// compensate for centripetal acceleration
|
|
|
|
|
|
|
|
veloc = _gps->ground_speed * 0.01; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// We are working with a modified version of equation 26 as
|
|
|
|
|
|
|
|
// our IMU object reports acceleration in the positive axis
|
|
|
|
|
|
|
|
// direction as positive
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Equation 26 broken up into separate pieces
|
|
|
|
|
|
|
|
accel.y -= _omega_integ_corr.z * veloc; |
|
|
|
|
|
|
|
accel.z += _omega_integ_corr.y * veloc; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
/*
|
|
|
|
reset the DCM matrix and omega. Used on ground start, and on |
|
|
|
reset the DCM matrix and omega. Used on ground start, and on |
|
|
|
extreme errors in the matrix |
|
|
|
extreme errors in the matrix |
|
|
@ -94,6 +124,7 @@ AP_AHRS_DCM::reset(bool recover_eulers) |
|
|
|
_omega_I.zero(); |
|
|
|
_omega_I.zero(); |
|
|
|
_omega_P.zero(); |
|
|
|
_omega_P.zero(); |
|
|
|
_omega_yaw_P.zero(); |
|
|
|
_omega_yaw_P.zero(); |
|
|
|
|
|
|
|
_omega_integ_corr.zero(); |
|
|
|
_omega.zero(); |
|
|
|
_omega.zero(); |
|
|
|
|
|
|
|
|
|
|
|
// if the caller wants us to try to recover to the current
|
|
|
|
// if the caller wants us to try to recover to the current
|
|
|
@ -228,262 +259,216 @@ AP_AHRS_DCM::normalize(void) |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// produce a yaw error value. The returned value is proportional
|
|
|
|
// perform drift correction. This function aims to update _omega_P and
|
|
|
|
// to sin() of the current heading error in earth frame
|
|
|
|
// _omega_I with our best estimate of the short term and long term
|
|
|
|
float |
|
|
|
// gyro error. The _omega_P value is what pulls our attitude solution
|
|
|
|
AP_AHRS_DCM::yaw_error_compass(void) |
|
|
|
// back towards the reference vector quickly. The _omega_I term is an
|
|
|
|
|
|
|
|
// attempt to learn the long term drift rate of the gyros.
|
|
|
|
|
|
|
|
//
|
|
|
|
|
|
|
|
// This function also updates _omega_yaw_P with a yaw correction term
|
|
|
|
|
|
|
|
// from our yaw reference vector
|
|
|
|
|
|
|
|
void |
|
|
|
|
|
|
|
AP_AHRS_DCM::drift_correction(float deltat) |
|
|
|
{ |
|
|
|
{ |
|
|
|
Vector3f mag = Vector3f(_compass->mag_x, _compass->mag_y, _compass->mag_z); |
|
|
|
float error_course = 0; |
|
|
|
// get the mag vector in the earth frame
|
|
|
|
Vector3f accel; |
|
|
|
Vector3f rb = _dcm_matrix * mag; |
|
|
|
Vector3f error; |
|
|
|
|
|
|
|
float error_norm = 0; |
|
|
|
rb.normalize(); |
|
|
|
float yaw_deltat = 0; |
|
|
|
if (rb.is_inf()) { |
|
|
|
|
|
|
|
// not a valid vector
|
|
|
|
accel = _accel_vector; |
|
|
|
return 0.0; |
|
|
|
|
|
|
|
|
|
|
|
// if enabled, use the GPS to correct our accelerometer vector
|
|
|
|
|
|
|
|
// for centripetal forces
|
|
|
|
|
|
|
|
if(_fly_forward && |
|
|
|
|
|
|
|
_gps != NULL && |
|
|
|
|
|
|
|
_gps->status() == GPS::GPS_OK) { |
|
|
|
|
|
|
|
accel_adjust(accel); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// get the earths magnetic field (only X and Y components needed)
|
|
|
|
|
|
|
|
Vector3f mag_earth = Vector3f(cos(_compass->get_declination()), |
|
|
|
|
|
|
|
sin(_compass->get_declination()), 0); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// calculate the error term in earth frame
|
|
|
|
//*****Roll and Pitch***************
|
|
|
|
Vector3f error = rb % mag_earth; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
return error.z; |
|
|
|
// normalise the accelerometer vector to a standard length
|
|
|
|
} |
|
|
|
// this is important to reduce the impact of noise on the
|
|
|
|
|
|
|
|
// drift correction, as very noisy vectors tend to have
|
|
|
|
|
|
|
|
// abnormally high lengths. By normalising the length we
|
|
|
|
|
|
|
|
// reduce their impact.
|
|
|
|
|
|
|
|
float accel_length = accel.length(); |
|
|
|
|
|
|
|
accel *= (_gravity / accel_length); |
|
|
|
|
|
|
|
if (accel.is_inf()) { |
|
|
|
|
|
|
|
// we can't do anything useful with this sample
|
|
|
|
|
|
|
|
_omega_P.zero(); |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// produce a yaw error value using the GPS. The returned value is proportional
|
|
|
|
// calculate the error, in m/2^2, between the attitude
|
|
|
|
// to sin() of the current heading error in earth frame
|
|
|
|
// implied by the accelerometers and the attitude
|
|
|
|
float |
|
|
|
// in the current DCM matrix
|
|
|
|
AP_AHRS_DCM::yaw_error_gps(void) |
|
|
|
error = _dcm_matrix.c % accel; |
|
|
|
{ |
|
|
|
|
|
|
|
return sin(ToRad(_gps->ground_course * 0.01) - yaw); |
|
|
|
// Limit max error to limit the effect of noisy values
|
|
|
|
} |
|
|
|
// on the algorithm. This limits the error to about 11
|
|
|
|
|
|
|
|
// degrees
|
|
|
|
|
|
|
|
error_norm = error.length(); |
|
|
|
|
|
|
|
if (error_norm > 2) { |
|
|
|
|
|
|
|
error *= (2 / error_norm); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// we now want to calculate _omega_P and _omega_I. The
|
|
|
|
|
|
|
|
// _omega_P value is what drags us quickly to the
|
|
|
|
|
|
|
|
// accelerometer reading.
|
|
|
|
|
|
|
|
_omega_P = error * _kp_roll_pitch; |
|
|
|
|
|
|
|
|
|
|
|
float |
|
|
|
// the _omega_I is the long term accumulated gyro
|
|
|
|
AP_AHRS_DCM::_P_gain(float spin_rate) |
|
|
|
// error. This determines how much gyro drift we can
|
|
|
|
{ |
|
|
|
// handle.
|
|
|
|
if (spin_rate < ToDeg(50)) { |
|
|
|
_omega_I_sum += error * (_ki_roll_pitch * deltat); |
|
|
|
return 1.0; |
|
|
|
_omega_I_sum_time += deltat; |
|
|
|
} |
|
|
|
|
|
|
|
if (spin_rate > ToDeg(500)) { |
|
|
|
|
|
|
|
return 10.0; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
return spin_rate/ToDeg(50); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// yaw drift correction using the compass or GPS
|
|
|
|
// these sums support the reporting of the DCM state via MAVLink
|
|
|
|
// this function prodoces the _omega_yaw_P vector, and also
|
|
|
|
_error_rp_sum += error_norm; |
|
|
|
// contributes to the _omega_I.z long term yaw drift estimate
|
|
|
|
_error_rp_count++; |
|
|
|
void |
|
|
|
|
|
|
|
AP_AHRS_DCM::drift_correction_yaw(void) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
bool new_value = false; |
|
|
|
|
|
|
|
float yaw_error; |
|
|
|
|
|
|
|
float yaw_deltat; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// yaw drift correction
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// we only do yaw drift correction when we get a new yaw
|
|
|
|
|
|
|
|
// reference vector. In between times we rely on the gyros for
|
|
|
|
|
|
|
|
// yaw. Avoiding this calculation on every call to
|
|
|
|
|
|
|
|
// update_DCM() saves a lot of time
|
|
|
|
if (_compass && _compass->use_for_yaw()) { |
|
|
|
if (_compass && _compass->use_for_yaw()) { |
|
|
|
if (_compass->last_update != _compass_last_update) { |
|
|
|
if (_compass->last_update != _compass_last_update) { |
|
|
|
yaw_deltat = (_compass->last_update - _compass_last_update) * 1.0e-6; |
|
|
|
yaw_deltat = 1.0e-6*(_compass->last_update - _compass_last_update); |
|
|
|
_compass_last_update = _compass->last_update; |
|
|
|
if (_have_initial_yaw && yaw_deltat < 2.0) { |
|
|
|
if (!_have_initial_yaw) { |
|
|
|
// Equation 23, Calculating YAW error
|
|
|
|
|
|
|
|
// We make the gyro YAW drift correction based
|
|
|
|
|
|
|
|
// on compass magnetic heading
|
|
|
|
|
|
|
|
float heading_x, heading_y; |
|
|
|
|
|
|
|
float heading = _compass->calculate_heading(_dcm_matrix); |
|
|
|
|
|
|
|
heading_x = cos(heading); |
|
|
|
|
|
|
|
heading_y = sin(heading); |
|
|
|
|
|
|
|
error_course = (_dcm_matrix.a.x * heading_y) - (_dcm_matrix.b.x * heading_x); |
|
|
|
|
|
|
|
_compass_last_update = _compass->last_update; |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
// this is our first estimate of the yaw,
|
|
|
|
|
|
|
|
// or the compass has come back online after
|
|
|
|
|
|
|
|
// no readings for 2 seconds.
|
|
|
|
|
|
|
|
//
|
|
|
|
|
|
|
|
// construct a DCM matrix based on the current
|
|
|
|
|
|
|
|
// roll/pitch and the compass heading.
|
|
|
|
|
|
|
|
// First ensure the compass heading has been
|
|
|
|
|
|
|
|
// calculated
|
|
|
|
float heading = _compass->calculate_heading(_dcm_matrix); |
|
|
|
float heading = _compass->calculate_heading(_dcm_matrix); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// now construct a new DCM matrix
|
|
|
|
_dcm_matrix.from_euler(roll, pitch, heading); |
|
|
|
_dcm_matrix.from_euler(roll, pitch, heading); |
|
|
|
_omega_yaw_P.zero(); |
|
|
|
|
|
|
|
_have_initial_yaw = true; |
|
|
|
_have_initial_yaw = true; |
|
|
|
|
|
|
|
_compass_last_update = _compass->last_update; |
|
|
|
|
|
|
|
error_course = 0; |
|
|
|
} |
|
|
|
} |
|
|
|
new_value = true; |
|
|
|
|
|
|
|
yaw_error = yaw_error_compass(); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} else if (_gps && _gps->status() == GPS::GPS_OK) { |
|
|
|
} else if (_gps && _gps->status() == GPS::GPS_OK) { |
|
|
|
if (_gps->last_fix_time != _gps_last_update && |
|
|
|
if (_gps->last_fix_time != _gps_last_update) { |
|
|
|
_gps->ground_speed >= GPS_SPEED_MIN) { |
|
|
|
// Use GPS Ground course to correct yaw gyro drift
|
|
|
|
yaw_deltat = (_gps->last_fix_time - _gps_last_update) * 1.0e-3; |
|
|
|
if (_gps->ground_speed >= GPS_SPEED_MIN) { |
|
|
|
_gps_last_update = _gps->last_fix_time; |
|
|
|
yaw_deltat = 1.0e-3*(_gps->last_fix_time - _gps_last_update); |
|
|
|
if (!_have_initial_yaw) { |
|
|
|
if (_have_initial_yaw && yaw_deltat < 2.0) { |
|
|
|
_dcm_matrix.from_euler(roll, pitch, ToRad(_gps->ground_course*0.01)); |
|
|
|
float course_over_ground_x = cos(ToRad(_gps->ground_course/100.0)); |
|
|
|
_omega_yaw_P.zero(); |
|
|
|
float course_over_ground_y = sin(ToRad(_gps->ground_course/100.0)); |
|
|
|
_have_initial_yaw = true; |
|
|
|
// Equation 23, Calculating YAW error
|
|
|
|
|
|
|
|
error_course = (_dcm_matrix.a.x * course_over_ground_y) - (_dcm_matrix.b.x * course_over_ground_x); |
|
|
|
|
|
|
|
_gps_last_update = _gps->last_fix_time; |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
// when we first start moving, set the
|
|
|
|
|
|
|
|
// DCM matrix to the current
|
|
|
|
|
|
|
|
// roll/pitch values, but with yaw
|
|
|
|
|
|
|
|
// from the GPS
|
|
|
|
|
|
|
|
_dcm_matrix.from_euler(roll, pitch, ToRad(_gps->ground_course)); |
|
|
|
|
|
|
|
_have_initial_yaw = true; |
|
|
|
|
|
|
|
error_course = 0; |
|
|
|
|
|
|
|
_gps_last_update = _gps->last_fix_time; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} else if (_gps->ground_speed >= GPS_SPEED_RESET) { |
|
|
|
|
|
|
|
// we are not going fast enough to use GPS for
|
|
|
|
|
|
|
|
// course correction, but we won't reset
|
|
|
|
|
|
|
|
// _have_initial_yaw yet, instead we just let
|
|
|
|
|
|
|
|
// the gyro handle yaw
|
|
|
|
|
|
|
|
error_course = 0; |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
// we are moving very slowly. Reset
|
|
|
|
|
|
|
|
// _have_initial_yaw and adjust our heading
|
|
|
|
|
|
|
|
// rapidly next time we get a good GPS ground
|
|
|
|
|
|
|
|
// speed
|
|
|
|
|
|
|
|
error_course = 0; |
|
|
|
|
|
|
|
_have_initial_yaw = false; |
|
|
|
} |
|
|
|
} |
|
|
|
new_value = true; |
|
|
|
|
|
|
|
yaw_error = yaw_error_gps(); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if (!new_value) { |
|
|
|
// see if there is any error in our heading relative to the
|
|
|
|
// we don't have any new yaw information
|
|
|
|
// yaw reference. This will be zero most of the time, as we
|
|
|
|
// slowly decay _omega_yaw_P to cope with loss
|
|
|
|
// only calculate it when we get new data from the yaw
|
|
|
|
// of our yaw source
|
|
|
|
// reference source
|
|
|
|
_omega_yaw_P.z *= 0.97; |
|
|
|
if (yaw_deltat == 0 || error_course == 0) { |
|
|
|
return; |
|
|
|
// we don't have a new reference heading. Slowly
|
|
|
|
|
|
|
|
// decay the _omega_yaw_P to ensure that if we have
|
|
|
|
|
|
|
|
// lost the yaw reference sensor completely we don't
|
|
|
|
|
|
|
|
// keep using a stale offset
|
|
|
|
|
|
|
|
_omega_yaw_P *= 0.97; |
|
|
|
|
|
|
|
goto check_sum_time; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// the yaw error is a vector in earth frame
|
|
|
|
// ensure the course error is scaled from -PI to PI
|
|
|
|
Vector3f error = Vector3f(0,0, yaw_error); |
|
|
|
if (error_course > PI) { |
|
|
|
|
|
|
|
error_course -= 2*PI; |
|
|
|
// convert the error vector to body frame
|
|
|
|
} else if (error_course < -PI) { |
|
|
|
error = _dcm_matrix.mul_transpose(error); |
|
|
|
error_course += 2*PI; |
|
|
|
|
|
|
|
|
|
|
|
// the spin rate changes the P gain, and disables the
|
|
|
|
|
|
|
|
// integration at higher rates
|
|
|
|
|
|
|
|
float spin_rate = _omega.length(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// update the proportional control to drag the
|
|
|
|
|
|
|
|
// yaw back to the right value. We use a gain
|
|
|
|
|
|
|
|
// that depends on the spin rate. See the fastRotations.pdf
|
|
|
|
|
|
|
|
// paper from Bill Premerlani
|
|
|
|
|
|
|
|
_omega_yaw_P = error * _P_gain(spin_rate) * _kp_yaw.get(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// don't update the drift term if we lost the yaw reference
|
|
|
|
|
|
|
|
// for more than 2 seconds
|
|
|
|
|
|
|
|
if (yaw_deltat < 2.0 && spin_rate < ToRad(SPIN_RATE_LIMIT)) { |
|
|
|
|
|
|
|
// also add to the I term
|
|
|
|
|
|
|
|
_omega_I_sum.z += error.z * _ki_yaw * yaw_deltat; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
_error_yaw_sum += fabs(yaw_error); |
|
|
|
// Equation 24, Applys the yaw correction to the XYZ rotation of the aircraft
|
|
|
|
|
|
|
|
// this gives us an error in radians
|
|
|
|
|
|
|
|
error = _dcm_matrix.c * error_course; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Adding yaw correction to proportional correction vector. We
|
|
|
|
|
|
|
|
// allow the yaw reference source to affect all 3 components
|
|
|
|
|
|
|
|
// of _omega_yaw_P as we need to be able to correctly hold a
|
|
|
|
|
|
|
|
// heading when roll and pitch are non-zero
|
|
|
|
|
|
|
|
_omega_yaw_P = error * _kp_yaw.get(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// add yaw correction to integrator correction vector, but
|
|
|
|
|
|
|
|
// only for the z gyro. We rely on the accelerometers for x
|
|
|
|
|
|
|
|
// and y gyro drift correction. Using the compass or GPS for
|
|
|
|
|
|
|
|
// x/y drift correction is too inaccurate, and can lead to
|
|
|
|
|
|
|
|
// incorrect builups in the x/y drift. We rely on the
|
|
|
|
|
|
|
|
// accelerometers to get the x/y components right
|
|
|
|
|
|
|
|
_omega_I_sum.z += error.z * (_ki_yaw * yaw_deltat); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// we keep the sum of yaw error for reporting via MAVLink.
|
|
|
|
|
|
|
|
_error_yaw_sum += error_course; |
|
|
|
_error_yaw_count++; |
|
|
|
_error_yaw_count++; |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
check_sum_time: |
|
|
|
|
|
|
|
if (_omega_I_sum_time > 10) { |
|
|
|
// perform drift correction. This function aims to update _omega_P and
|
|
|
|
// every 10 seconds we apply the accumulated
|
|
|
|
// _omega_I with our best estimate of the short term and long term
|
|
|
|
// _omega_I_sum changes to _omega_I. We do this to
|
|
|
|
// gyro error. The _omega_P value is what pulls our attitude solution
|
|
|
|
// prevent short term feedback between the P and I
|
|
|
|
// back towards the reference vector quickly. The _omega_I term is an
|
|
|
|
// terms of the controller. The _omega_I vector is
|
|
|
|
// attempt to learn the long term drift rate of the gyros.
|
|
|
|
// supposed to refect long term gyro drift, but with
|
|
|
|
//
|
|
|
|
// high noise it can start to build up due to short
|
|
|
|
// This drift correction implementation is based on a paper
|
|
|
|
// term interactions. By summing it over 10 seconds we
|
|
|
|
// by Bill Premerlani from here:
|
|
|
|
// prevent the short term interactions and can apply
|
|
|
|
// http://gentlenav.googlecode.com/files/RollPitchDriftCompensation.pdf
|
|
|
|
// the slope limit more accurately
|
|
|
|
void |
|
|
|
float drift_limit = _gyro_drift_limit * _omega_I_sum_time; |
|
|
|
AP_AHRS_DCM::drift_correction(float deltat) |
|
|
|
_omega_I_sum.x = constrain(_omega_I_sum.x, -drift_limit, drift_limit); |
|
|
|
{ |
|
|
|
_omega_I_sum.y = constrain(_omega_I_sum.y, -drift_limit, drift_limit); |
|
|
|
Vector3f error; |
|
|
|
_omega_I_sum.z = constrain(_omega_I_sum.z, -drift_limit, drift_limit); |
|
|
|
Vector3f velocity; |
|
|
|
|
|
|
|
uint32_t last_correction_time; |
|
|
|
_omega_I += _omega_I_sum; |
|
|
|
bool use_gps = true; |
|
|
|
|
|
|
|
|
|
|
|
// zero the sum
|
|
|
|
// perform yaw drift correction if we have a new yaw reference
|
|
|
|
_omega_I_sum.zero(); |
|
|
|
// vector
|
|
|
|
_omega_I_sum_time = 0; |
|
|
|
drift_correction_yaw(); |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// integrate the accel vector in the earth frame between GPS readings
|
|
|
|
|
|
|
|
_ra_sum += _dcm_matrix * (_accel_vector * deltat); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// keep a sum of the deltat values, so we know how much time
|
|
|
|
|
|
|
|
// we have integrated over
|
|
|
|
|
|
|
|
_ra_deltat += deltat; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// check if we have GPS lock
|
|
|
|
|
|
|
|
if (_gps == NULL || _gps->status() != GPS::GPS_OK) { |
|
|
|
|
|
|
|
use_gps = false; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// a copter (which has _fly_forward false) which doesn't have a
|
|
|
|
|
|
|
|
// compass for yaw can't rely on the GPS velocity lining up with
|
|
|
|
|
|
|
|
// the earth frame from DCM, so it needs to assume zero velocity
|
|
|
|
|
|
|
|
// in the drift correction
|
|
|
|
|
|
|
|
if (!_fly_forward && !(_compass && _compass->use_for_yaw())) { |
|
|
|
|
|
|
|
use_gps = false; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (use_gps == false) { |
|
|
|
|
|
|
|
// no GPS, or no lock. We assume zero velocity. This at
|
|
|
|
|
|
|
|
// least means we can cope with gyro drift while sitting
|
|
|
|
|
|
|
|
// on a bench with no GPS lock
|
|
|
|
|
|
|
|
if (_ra_deltat < 0.1) { |
|
|
|
|
|
|
|
// not enough time has accumulated
|
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
velocity.zero(); |
|
|
|
|
|
|
|
_last_velocity.zero(); |
|
|
|
|
|
|
|
last_correction_time = millis(); |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
if (_gps->last_fix_time == _ra_sum_start) { |
|
|
|
|
|
|
|
// we don't have a new GPS fix - nothing more to do
|
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
velocity = Vector3f(_gps->velocity_north(), _gps->velocity_east(), 0); |
|
|
|
|
|
|
|
last_correction_time = _gps->last_fix_time; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// even without GPS lock we can correct for the vertical acceleration
|
|
|
|
|
|
|
|
if (_barometer != NULL) { |
|
|
|
|
|
|
|
// Z velocity is down
|
|
|
|
|
|
|
|
velocity.z = - _barometer->get_climb_rate(); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// see if this is our first time through - in which case we
|
|
|
|
|
|
|
|
// just setup the start times and return
|
|
|
|
|
|
|
|
if (_ra_sum_start == 0) { |
|
|
|
|
|
|
|
_ra_sum_start = last_correction_time; |
|
|
|
|
|
|
|
_last_velocity = velocity; |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// get the corrected acceleration vector in earth frame. Units
|
|
|
|
|
|
|
|
// are m/s/s
|
|
|
|
|
|
|
|
Vector3f ge; |
|
|
|
|
|
|
|
float v_scale = 1.0/(_ra_deltat*_gravity); |
|
|
|
|
|
|
|
ge = Vector3f(0, 0, -1.0) + ((velocity - _last_velocity) * v_scale); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// calculate the error term in earth frame.
|
|
|
|
|
|
|
|
ge.normalize(); |
|
|
|
|
|
|
|
_ra_sum.normalize(); |
|
|
|
|
|
|
|
if (_ra_sum.is_inf() || ge.is_inf()) { |
|
|
|
|
|
|
|
// the _ra_sum length is zero - we are falling with
|
|
|
|
|
|
|
|
// no apparent gravity. This gives us no information
|
|
|
|
|
|
|
|
// about which way up we are, so treat the error as zero
|
|
|
|
|
|
|
|
error = Vector3f(0,0,0); |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
error = _ra_sum % ge; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
_error_rp_sum += error.length(); |
|
|
|
|
|
|
|
_error_rp_count++; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// convert the error term to body frame
|
|
|
|
|
|
|
|
error = _dcm_matrix.mul_transpose(error); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// base the P gain on the spin rate
|
|
|
|
|
|
|
|
float spin_rate = _omega.length(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// we now want to calculate _omega_P and _omega_I. The
|
|
|
|
|
|
|
|
// _omega_P value is what drags us quickly to the
|
|
|
|
|
|
|
|
// accelerometer reading.
|
|
|
|
|
|
|
|
_omega_P = error * _P_gain(spin_rate) * _kp; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// accumulate some integrator error
|
|
|
|
|
|
|
|
if (spin_rate < ToRad(SPIN_RATE_LIMIT)) { |
|
|
|
|
|
|
|
_omega_I_sum += error * _ki * _ra_deltat; |
|
|
|
|
|
|
|
_omega_I_sum_time += _ra_deltat; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (_omega_I_sum_time >= 5) { |
|
|
|
|
|
|
|
// limit the rate of change of omega_I to the hardware
|
|
|
|
|
|
|
|
// reported maximum gyro drift rate. This ensures that
|
|
|
|
|
|
|
|
// short term errors don't cause a buildup of omega_I
|
|
|
|
|
|
|
|
// beyond the physical limits of the device
|
|
|
|
|
|
|
|
float change_limit = _gyro_drift_limit * _omega_I_sum_time; |
|
|
|
|
|
|
|
_omega_I_sum.x = constrain(_omega_I_sum.x, -change_limit, change_limit); |
|
|
|
|
|
|
|
_omega_I_sum.y = constrain(_omega_I_sum.y, -change_limit, change_limit); |
|
|
|
|
|
|
|
_omega_I_sum.z = constrain(_omega_I_sum.z, -change_limit, change_limit); |
|
|
|
|
|
|
|
_omega_I += _omega_I_sum; |
|
|
|
|
|
|
|
_omega_I_sum.zero(); |
|
|
|
|
|
|
|
_omega_I_sum_time = 0; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// zero our accumulator ready for the next GPS step
|
|
|
|
|
|
|
|
_ra_sum.zero(); |
|
|
|
|
|
|
|
_ra_deltat = 0; |
|
|
|
|
|
|
|
_ra_sum_start = last_correction_time; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// remember the velocity for next time
|
|
|
|
|
|
|
|
_last_velocity = velocity; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|