From 7fc37e7801479ccbdd0cfdc8884a3ed73d31d3a6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 3 Feb 2016 18:01:50 +0900 Subject: [PATCH] Copter: set tradheli external gyro gain in 0 to 1 range --- ArduCopter/tuning.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index 54f174015c..156ef543b6 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -111,7 +111,7 @@ void Copter::tuning() { #if FRAME_CONFIG == HELI_FRAME case TUNING_HELI_EXTERNAL_GYRO: - motors.ext_gyro_gain(g.rc_6.control_in); + motors.ext_gyro_gain((float)g.rc_6.control_in / 1000.0f); break; case TUNING_RATE_PITCH_FF: