GCS_MAVLink: send AHRS2 even if we don't have a secondary position

This commit is contained in:
Andrew Tridgell 2015-07-13 16:07:40 +10:00
parent 6009ae55b1
commit 18de1c2c47
1 changed files with 2 additions and 2 deletions

View File

@ -218,8 +218,8 @@ void GCS_MAVLINK::send_ahrs2(AP_AHRS &ahrs)
{
#if AP_AHRS_NAVEKF_AVAILABLE
Vector3f euler;
struct Location loc;
if (ahrs.get_secondary_attitude(euler) && ahrs.get_secondary_position(loc)) {
struct Location loc {};
if (ahrs.get_secondary_attitude(euler)) {
mavlink_msg_ahrs2_send(chan,
euler.x,
euler.y,