mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Plane: use common send_ahrs2()
This commit is contained in:
parent
9aea781248
commit
4646682a31
@ -527,24 +527,6 @@ static void NOINLINE send_simstate(mavlink_channel_t chan)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// report NavEKF state
|
|
||||||
static void NOINLINE send_ekf(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
Vector3f euler;
|
|
||||||
struct Location loc;
|
|
||||||
if (ahrs.get_secondary_attitude(euler) && ahrs.get_secondary_position(loc)) {
|
|
||||||
mavlink_msg_ahrs2_send(chan,
|
|
||||||
euler.x,
|
|
||||||
euler.y,
|
|
||||||
euler.z,
|
|
||||||
loc.alt*1.0e-2f,
|
|
||||||
loc.lat,
|
|
||||||
loc.lng);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_hwstatus_send(
|
mavlink_msg_hwstatus_send(
|
||||||
@ -745,7 +727,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id)
|
|||||||
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
||||||
send_simstate(chan);
|
send_simstate(chan);
|
||||||
CHECK_PAYLOAD_SIZE(AHRS2);
|
CHECK_PAYLOAD_SIZE(AHRS2);
|
||||||
send_ekf(chan);
|
gcs[chan-MAVLINK_COMM_0].send_ahrs2(ahrs);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_HWSTATUS:
|
case MSG_HWSTATUS:
|
||||||
|
Loading…
Reference in New Issue
Block a user