Browse Source

AP_AHRS: use the right DCM matrix when EKF not enabled

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
ada7d4fb98
  1. 2
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

2
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -33,7 +33,7 @@ const Vector3f AP_AHRS_NavEKF::get_gyro(void) const @@ -33,7 +33,7 @@ const Vector3f AP_AHRS_NavEKF::get_gyro(void) const
const Matrix3f &AP_AHRS_NavEKF::get_dcm_matrix(void) const
{
if (!ekf_started) {
if (!using_EKF()) {
return AP_AHRS_DCM::get_dcm_matrix();
}
return _dcm_matrix;

Loading…
Cancel
Save