mirror of https://github.com/ArduPilot/ardupilot
Compass: change last_update to be in microseconds
This commit is contained in:
parent
404a4e4896
commit
17daa2f31c
|
@ -16,7 +16,7 @@
|
|||
bool AP_Compass_HIL::read()
|
||||
{
|
||||
// values set by setHIL function
|
||||
last_update = millis(); // record time of update
|
||||
last_update = micros(); // record time of update
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -279,7 +279,7 @@ bool AP_Compass_HMC5843::read()
|
|||
mag_y *= calibration[1];
|
||||
mag_z *= calibration[2];
|
||||
|
||||
last_update = millis(); // record time of update
|
||||
last_update = micros(); // record time of update
|
||||
// rotate and offset the magnetometer values
|
||||
// XXX this could well be done in common code...
|
||||
|
||||
|
|
Loading…
Reference in New Issue