From 0743b979fa71f0f65b6d1a0326327ef5214dfe9d Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 12 Mar 2019 02:45:14 -0700 Subject: [PATCH] AP_Logger: Don't log AHR2 unless the quat is available This should not be a functional change, because if the secondary attitude is available then the secondary quat will be as well --- libraries/AP_Logger/LogFile.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 8b177fefe1..e69cec2153 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -473,10 +473,9 @@ void AP_Logger::Write_AHRS2(AP_AHRS &ahrs) Vector3f euler; struct Location loc; Quaternion quat; - if (!ahrs.get_secondary_attitude(euler) || !ahrs.get_secondary_position(loc)) { + if (!ahrs.get_secondary_attitude(euler) || !ahrs.get_secondary_position(loc) || !ahrs.get_secondary_quaternion(quat)) { return; } - ahrs.get_secondary_quaternion(quat); struct log_AHRS pkt = { LOG_PACKET_HEADER_INIT(LOG_AHR2_MSG), time_us : AP_HAL::micros64(),