mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Fix bug in transposed DCM matrix accessor
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1134 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e194e2fa75
commit
1da23bc3c0
@ -52,33 +52,6 @@ AP_DCM::update_DCM(float _G_Dt)
|
||||
}
|
||||
|
||||
/**************************************************/
|
||||
Vector3f
|
||||
AP_DCM::get_gyro(void)
|
||||
{
|
||||
return _omega_integ_corr;
|
||||
} // We return the raw gyro vector corrected for bias
|
||||
|
||||
/**************************************************/
|
||||
Vector3f
|
||||
AP_DCM::get_accel(void)
|
||||
{
|
||||
return _accel_vector;
|
||||
}
|
||||
|
||||
/**************************************************/
|
||||
Matrix3f
|
||||
AP_DCM::get_dcm_matrix(void)
|
||||
{
|
||||
return _dcm_matrix;
|
||||
}
|
||||
|
||||
/**************************************************/
|
||||
Matrix3f
|
||||
AP_DCM::get_dcm_transposed(void)
|
||||
{
|
||||
return _dcm_matrix.transpose();
|
||||
}
|
||||
|
||||
|
||||
//For Debugging
|
||||
/*
|
||||
|
@ -44,10 +44,10 @@ public:
|
||||
{}
|
||||
|
||||
// Accessors
|
||||
Vector3f get_gyro(void);
|
||||
Vector3f get_accel(void);
|
||||
Matrix3f get_dcm_matrix(void);
|
||||
Matrix3f get_dcm_transposed(void);
|
||||
Vector3f get_gyro(void) {return _omega_integ_corr; } // We return the raw gyro vector corrected for bias
|
||||
Vector3f get_accel(void) { return _accel_vector; }
|
||||
Matrix3f get_dcm_matrix(void) {return _dcm_matrix; }
|
||||
Matrix3f get_dcm_transposed(void) {Matrix3f temp = _dcm_matrix; return temp.transpose();}
|
||||
|
||||
void set_centripetal(bool b);
|
||||
void set_compass(Compass *compass);
|
||||
|
@ -25,6 +25,7 @@ public:
|
||||
Vector3f get_gyro(void) {return _omega_integ_corr; }
|
||||
Vector3f get_accel(void) { return _accel_vector; }
|
||||
Matrix3f get_dcm_matrix(void) {return _dcm_matrix; }
|
||||
Matrix3f get_dcm_transposed(void) {Matrix3f temp = _dcm_matrix; return temp.transpose();}
|
||||
|
||||
void set_centripetal(bool b) {}
|
||||
void set_compass(Compass *compass) {}
|
||||
|
Loading…
Reference in New Issue
Block a user