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
This commit is contained in:
Michael du Breuil 2019-03-12 02:45:14 -07:00 committed by Andrew Tridgell
parent 8e8ce6be35
commit 0743b979fa
1 changed files with 1 additions and 2 deletions

View File

@ -473,10 +473,9 @@ void AP_Logger::Write_AHRS2(AP_AHRS &ahrs)
Vector3f euler; Vector3f euler;
struct Location loc; struct Location loc;
Quaternion quat; 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; return;
} }
ahrs.get_secondary_quaternion(quat);
struct log_AHRS pkt = { struct log_AHRS pkt = {
LOG_PACKET_HEADER_INIT(LOG_AHR2_MSG), LOG_PACKET_HEADER_INIT(LOG_AHR2_MSG),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),