mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_AHRS: make DCM use milligauss
This commit is contained in:
parent
b5b6d767bd
commit
4b948f5bb1
@ -276,7 +276,7 @@ AP_AHRS_DCM::normalize(void)
|
|||||||
float
|
float
|
||||||
AP_AHRS_DCM::yaw_error_compass(void)
|
AP_AHRS_DCM::yaw_error_compass(void)
|
||||||
{
|
{
|
||||||
const Vector3f &mag = _compass->get_field();
|
const Vector3f &mag = _compass->get_field_milligauss();
|
||||||
// get the mag vector in the earth frame
|
// get the mag vector in the earth frame
|
||||||
Vector2f rb = _dcm_matrix.mulXY(mag);
|
Vector2f rb = _dcm_matrix.mulXY(mag);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user