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:
Andrew Tridgell 2014-03-23 22:05:17 +11:00
parent 60a4f74de6
commit 485ae596fc

View File

@ -129,9 +129,9 @@ bool AP_Compass_PX4::read(void)
_count[i] = 0; _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) void AP_Compass_PX4::accumulate(void)