Browse Source

AP_AHRS: use compass get_{field,offsets}() functions

Both functions are equivalent, so we're going to simply use
get_{field,offsets}() instead of get_{field,offsets}_milligauss().
mission-4.1.18
Gustavo Jose de Sousa 9 years ago committed by Randy Mackay
parent
commit
84f811fe76
  1. 2
      libraries/AP_AHRS/AP_AHRS_DCM.cpp

2
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -276,7 +276,7 @@ AP_AHRS_DCM::normalize(void) @@ -276,7 +276,7 @@ AP_AHRS_DCM::normalize(void)
float
AP_AHRS_DCM::yaw_error_compass(void)
{
const Vector3f &mag = _compass->get_field_milligauss();
const Vector3f &mag = _compass->get_field();
// get the mag vector in the earth frame
Vector2f rb = _dcm_matrix.mulXY(mag);

Loading…
Cancel
Save