From 7480a2a00bdfbc49af6f85eaaab55c55e6ee2c5b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Mar 2021 15:42:50 +1100 Subject: [PATCH] GCS_MAVLink: correct output of AHRS2 mavlink message The || here was causing short-circuiting --- libraries/GCS_MAVLink/GCS_Common.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 36eb0c1614..1c3ba7d941 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -437,7 +437,8 @@ void GCS_MAVLINK::send_ahrs2() const AP_AHRS &ahrs = AP::ahrs(); Vector3f euler; struct Location loc {}; - if (ahrs.get_secondary_attitude(euler) || + // we want one or both of these, use | to avoid short-circuiting: + if (ahrs.get_secondary_attitude(euler) | ahrs.get_secondary_position(loc)) { mavlink_msg_ahrs2_send(chan, euler.x,