mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
APA_AHRS: update for compass API change
This commit is contained in:
parent
65c97a2f5f
commit
baa4ecc2ea
@ -244,7 +244,7 @@ AP_AHRS_DCM::normalize(void)
|
|||||||
float
|
float
|
||||||
AP_AHRS_DCM::yaw_error_compass(void)
|
AP_AHRS_DCM::yaw_error_compass(void)
|
||||||
{
|
{
|
||||||
Vector3f mag = Vector3f(_compass->mag_x, _compass->mag_y, _compass->mag_z);
|
const Vector3f &mag = _compass->get_field();
|
||||||
// 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