Copter: tuning rc-feel uses multiply instead of divide

This commit is contained in:
Randy Mackay 2018-02-08 11:21:56 +09:00
parent 92b56c2c89
commit 0392d2752d

View File

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