mirror of https://github.com/ArduPilot/ardupilot
Compass: fixed last_update time for HIL compass
This commit is contained in:
parent
2969e16f7d
commit
8b73166605
|
@ -16,6 +16,7 @@
|
||||||
bool AP_Compass_HIL::read()
|
bool AP_Compass_HIL::read()
|
||||||
{
|
{
|
||||||
// values set by setHIL function
|
// values set by setHIL function
|
||||||
|
last_update = millis(); // record time of update
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue