Browse Source

Fix bug in transposed DCM matrix accessor

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1134 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
deweibel 14 years ago
parent
commit
1da23bc3c0
  1. 27
      libraries/AP_DCM/AP_DCM.cpp
  2. 8
      libraries/AP_DCM/AP_DCM.h
  3. 1
      libraries/AP_DCM/AP_DCM_HIL.h

27
libraries/AP_DCM/AP_DCM.cpp

@ -52,33 +52,6 @@ AP_DCM::update_DCM(float _G_Dt) @@ -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
/*

8
libraries/AP_DCM/AP_DCM.h

@ -44,10 +44,10 @@ public: @@ -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);

1
libraries/AP_DCM/AP_DCM_HIL.h

@ -25,6 +25,7 @@ public: @@ -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…
Cancel
Save