AP_AHRS: rename get_dcm_matrix to get_rotation_body_to_ned

This commit is contained in:
Jonathan Challinger 2015-12-10 14:05:13 -08:00 committed by Andrew Tridgell
parent 2a953c4e35
commit 6682b27456
6 changed files with 8 additions and 8 deletions

View File

@ -231,7 +231,7 @@ Vector2f AP_AHRS::groundspeed_vector(void)
void AP_AHRS::update_trig(void) void AP_AHRS::update_trig(void)
{ {
Vector2f yaw_vector; Vector2f yaw_vector;
const Matrix3f &temp = get_dcm_matrix(); const Matrix3f &temp = get_rotation_body_to_ned();
// sin_yaw, cos_yaw // sin_yaw, cos_yaw
yaw_vector.x = temp.a.x; yaw_vector.x = temp.a.x;

View File

@ -178,7 +178,7 @@ public:
// get yaw rate in earth frame in radians/sec // get yaw rate in earth frame in radians/sec
float get_yaw_rate_earth(void) const { float get_yaw_rate_earth(void) const {
return get_gyro() * get_dcm_matrix().c; return get_gyro() * get_rotation_body_to_ned().c;
} }
// Methods // Methods
@ -225,7 +225,7 @@ public:
// return a DCM rotation matrix representing our current // return a DCM rotation matrix representing our current
// attitude // attitude
virtual const Matrix3f &get_dcm_matrix(void) const = 0; virtual const Matrix3f &get_rotation_body_to_ned(void) const = 0;
// get our current position estimate. Return true if a position is available, // get our current position estimate. Return true if a position is available,
// otherwise false. This call fills in lat, lng and alt // otherwise false. This call fills in lat, lng and alt

View File

@ -65,7 +65,7 @@ public:
} }
// return rotation matrix representing rotaton from body to earth axes // return rotation matrix representing rotaton from body to earth axes
const Matrix3f &get_dcm_matrix(void) const { const Matrix3f &get_rotation_body_to_ned(void) const {
return _body_dcm_matrix; return _body_dcm_matrix;
} }

View File

@ -48,10 +48,10 @@ const Vector3f &AP_AHRS_NavEKF::get_gyro(void) const
return _gyro_estimate; return _gyro_estimate;
} }
const Matrix3f &AP_AHRS_NavEKF::get_dcm_matrix(void) const const Matrix3f &AP_AHRS_NavEKF::get_rotation_body_to_ned(void) const
{ {
if (!active_EKF_type()) { if (!active_EKF_type()) {
return AP_AHRS_DCM::get_dcm_matrix(); return AP_AHRS_DCM::get_rotation_body_to_ned();
} }
return _dcm_matrix; return _dcm_matrix;
} }

View File

@ -51,7 +51,7 @@ public:
// return the smoothed gyro vector corrected for drift // return the smoothed gyro vector corrected for drift
const Vector3f &get_gyro(void) const; const Vector3f &get_gyro(void) const;
const Matrix3f &get_dcm_matrix(void) const; const Matrix3f &get_rotation_body_to_ned(void) const;
// return the current drift correction integrator value // return the current drift correction integrator value
const Vector3f &get_gyro_drift(void) const; const Vector3f &get_gyro_drift(void) const;

View File

@ -57,7 +57,7 @@ void loop(void)
if (now - last_compass > 100*1000UL && if (now - last_compass > 100*1000UL &&
compass.read()) { compass.read()) {
heading = compass.calculate_heading(ahrs.get_dcm_matrix()); heading = compass.calculate_heading(ahrs.get_rotation_body_to_ned());
// read compass at 10Hz // read compass at 10Hz
last_compass = now; last_compass = now;
#if WITH_GPS #if WITH_GPS