From 99d21854f9febe83f21c8ea452d8c6b45aa5a7db Mon Sep 17 00:00:00 2001 From: Andrew Tridgell <tridge@samba.org> Date: Sat, 4 May 2013 15:16:35 +1000 Subject: [PATCH] SITL: fixed drift rate limit in simulator --- libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp index 488036a2fd..4909f5ea0c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp @@ -41,7 +41,8 @@ uint32_t AP_InertialSensor_Stub::get_last_sample_time_micros() { return _last_update_ms * 1000; } float AP_InertialSensor_Stub::get_gyro_drift_rate(void) { - return 0.0; + // 0.5 degrees/second/minute + return ToRad(0.5/60); } uint16_t AP_InertialSensor_Stub::num_samples_available() {