Browse Source

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

mission-4.1.18
rmackay9 12 years ago committed by Andrew Tridgell
parent
commit
1c08f176ea
  1. 6
      libraries/AP_AHRS/AP_AHRS.h
  2. 5
      libraries/AP_AHRS/AP_AHRS_DCM.cpp
  3. 3
      libraries/AP_AHRS/AP_AHRS_MPU6000.cpp

6
libraries/AP_AHRS/AP_AHRS.h

@ -62,6 +62,9 @@ public: @@ -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: @@ -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;

5
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -393,8 +393,11 @@ AP_AHRS_DCM::drift_correction(float deltat) @@ -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

3
libraries/AP_AHRS/AP_AHRS_MPU6000.cpp

@ -66,6 +66,9 @@ AP_AHRS_MPU6000::update(void) @@ -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

Loading…
Cancel
Save