mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Compass: fixed last_update for secondary compass with primary failed
this ensures EKF and DCM will use a secondary compass if the primary fails
This commit is contained in:
parent
60a4f74de6
commit
485ae596fc
@ -129,9 +129,9 @@ bool AP_Compass_PX4::read(void)
|
||||
_count[i] = 0;
|
||||
}
|
||||
|
||||
last_update = _last_timestamp[0];
|
||||
last_update = _last_timestamp[_get_primary()];
|
||||
|
||||
return _healthy[0];
|
||||
return _healthy[_get_primary()];
|
||||
}
|
||||
|
||||
void AP_Compass_PX4::accumulate(void)
|
||||
|
Loading…
Reference in New Issue
Block a user