mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
Plane: switched to AHRS2 message for reporting
This commit is contained in:
parent
ea0f9392ef
commit
99cfaf6097
@ -533,15 +533,15 @@ static void NOINLINE send_ekf(mavlink_channel_t chan)
|
|||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
Vector3f euler;
|
Vector3f euler;
|
||||||
struct Location loc;
|
struct Location loc;
|
||||||
ahrs.get_NavEKF().getEulerAngles(euler);
|
if (ahrs.get_secondary_attitude(euler) && ahrs.get_secondary_position(loc)) {
|
||||||
ahrs.get_NavEKF().getLLH(loc);
|
mavlink_msg_ahrs2_send(chan,
|
||||||
mavlink_msg_ekf_send(chan,
|
euler.x,
|
||||||
euler.x,
|
euler.y,
|
||||||
euler.y,
|
euler.z,
|
||||||
euler.z,
|
loc.alt*1.0e-2f,
|
||||||
loc.alt*1.0e-2f,
|
loc.lat,
|
||||||
loc.lat,
|
loc.lng);
|
||||||
loc.lng);
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -744,7 +744,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id)
|
|||||||
case MSG_SIMSTATE:
|
case MSG_SIMSTATE:
|
||||||
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
||||||
send_simstate(chan);
|
send_simstate(chan);
|
||||||
CHECK_PAYLOAD_SIZE(EKF);
|
CHECK_PAYLOAD_SIZE(AHRS2);
|
||||||
send_ekf(chan);
|
send_ekf(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user