From 17daa2f31cfdd43bbb948bb48147fe5167f321e3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Mar 2012 15:14:59 +1100 Subject: [PATCH] Compass: change last_update to be in microseconds --- libraries/AP_Compass/AP_Compass_HIL.cpp | 2 +- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_HIL.cpp b/libraries/AP_Compass/AP_Compass_HIL.cpp index f57d7f5320..1e3187a343 100644 --- a/libraries/AP_Compass/AP_Compass_HIL.cpp +++ b/libraries/AP_Compass/AP_Compass_HIL.cpp @@ -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; } diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index dc452baad7..a34bf8c424 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -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...