From bb72f91dda72fae062a5c75ad593f510e3f9356f Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 12 Mar 2022 02:40:11 +0900 Subject: [PATCH] APM_Control: Change from division to multiplication --- libraries/APM_Control/AP_YawController.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index b72608c9e3..913f2c62e4 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -173,7 +173,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator) aspd_min = 1; } - float delta_time = (float) dt / 1000.0f; + float delta_time = (float) dt * 0.001f; // Calculate yaw rate required to keep up with a constant height coordinated turn float aspeed;