From 1bb18bc9415f43d48b4ad2b146706333f4682376 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 5 Jan 2018 11:34:31 +0900 Subject: [PATCH] AR_AttitudeControl: get_throttle_out_speed uses timeout definition --- libraries/APM_Control/AR_AttitudeControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index dc8209917f..2c72a293e2 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -320,7 +320,7 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor // calculate dt const uint32_t now = AP_HAL::millis(); float dt = (now - _speed_last_ms) / 1000.0f; - if (_speed_last_ms == 0 || dt > 0.1f) { + if ((_speed_last_ms == 0) || (dt > (AR_ATTCONTROL_TIMEOUT_MS / 1000.0f))) { dt = 0.0f; _throttle_speed_pid.reset_filter(); } else {