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().
This commit is contained in:
Gustavo Jose de Sousa 2015-09-28 16:53:32 -03:00 committed by Randy Mackay
parent 4375606eeb
commit 84f811fe76
1 changed files with 1 additions and 1 deletions

View File

@ -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);