diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index 309076c95c..1f58ed0b45 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -143,7 +143,7 @@ void Copter::heli_update_rotor_speed_targets() // get rotor control method uint8_t rsc_control_mode = motors.get_rsc_mode(); - float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)g.rc_8.get_control_in()/1000.0f); + float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)g.rc_8.get_control_in()) * 0.001f; switch (rsc_control_mode) { case ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH: