From 0392d2752def7af412f9158cc4379cb0d5533d96 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 8 Feb 2018 11:21:56 +0900 Subject: [PATCH] Copter: tuning rc-feel uses multiply instead of divide --- ArduCopter/tuning.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index 305eb11612..b9a8f3d7f8 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -180,7 +180,7 @@ void Copter::tuning() { case TUNING_RC_FEEL_RP: // convert from control_in to input time constant - attitude_control->set_input_tc(1.0f / (2.f + MAX((control_in/100.0f),0.0f))); + attitude_control->set_input_tc(1.0f / (2.0f + MAX((control_in * 0.01f), 0.0f))); break; case TUNING_RATE_PITCH_KP: