mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
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:
parent
8e8ce6be35
commit
0743b979fa
@ -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(),
|
||||
|
Loading…
Reference in New Issue
Block a user