From 3617c65af7d584733bd9ba6e260fa96b7420f9ff Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 5 Jan 2014 21:24:03 +0800 Subject: [PATCH] AP_InertialSensor: make HIL treat time like PX4 does --- libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp index b3996dd50c..28ee41a6b6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp @@ -33,7 +33,7 @@ bool AP_InertialSensor_HIL::update( void ) { } float AP_InertialSensor_HIL::get_delta_time() const { - return _delta_time_usec * 1.0e-6; + return _sample_period_ms * 0.001f; } float AP_InertialSensor_HIL::get_gyro_drift_rate(void) {