Copter: set tradheli external gyro gain in 0 to 1 range

This commit is contained in:
Randy Mackay 2016-02-03 18:01:50 +09:00
parent fe4733121d
commit 7fc37e7801
1 changed files with 1 additions and 1 deletions

View File

@ -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: