From 18de1c2c47ec0a8709712865511e7910e8850db2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Jul 2015 16:07:40 +1000 Subject: [PATCH] GCS_MAVLink: send AHRS2 even if we don't have a secondary position --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a9a93abd62..e09efd739f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -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,