AP_AHRS: add get_accel_ef method to return earth frame accelerometer values for use in ArduCopter's inertial nav and accel based throttle

This commit is contained in:
rmackay9 2012-12-12 16:22:56 +09:00 committed by Andrew Tridgell
parent 4dfe3a2d73
commit 1c08f176ea
3 changed files with 13 additions and 1 deletions

View File

@ -62,6 +62,9 @@ public:
return _ins;
}
// accelerometer values in the earth frame in m/s/s
Vector3f get_accel_ef(void) { return _accel_ef; }
// Methods
virtual void update(void) = 0;
@ -192,6 +195,9 @@ protected:
// radians/s/s
float _gyro_drift_limit;
// accelerometer values in the earth frame in m/s/s
Vector3f _accel_ef;
// acceleration due to gravity in m/s/s
static const float _gravity = 9.80665;

View File

@ -393,8 +393,11 @@ AP_AHRS_DCM::drift_correction(float deltat)
// apply trim
temp_dcm.rotate(_trim);
// rotate accelerometer values into the earth frame
_accel_ef = temp_dcm * _accel_vector;
// integrate the accel vector in the earth frame between GPS readings
_ra_sum += temp_dcm * (_accel_vector * deltat);
_ra_sum += _accel_ef * deltat;
// keep a sum of the deltat values, so we know how much time
// we have integrated over

View File

@ -66,6 +66,9 @@ AP_AHRS_MPU6000::update(void)
// Calculate pitch, roll, yaw for stabilization and navigation
euler_angles();
// prepare earth frame accelerometer values for ArduCopter Inertial Navigation and accel-based throttle
_accel_ef = _dcm_matrix * _ins->get_accel();
}
// wrap_PI - ensure an angle (expressed in radians) is between -PI and PI