diff --git a/ArduPlane/motor_test.cpp b/ArduPlane/motor_test.cpp index 98b019a4e4..d5866772ff 100644 --- a/ArduPlane/motor_test.cpp +++ b/ArduPlane/motor_test.cpp @@ -57,7 +57,7 @@ void QuadPlane::motor_test_output() break; case MOTOR_TEST_THROTTLE_PILOT: - pwm = plane.channel_throttle->get_radio_in(); + pwm = thr_min_pwm + (thr_max_pwm - thr_min_pwm) * (float)plane.channel_throttle->get_control_in()*0.01f; break; default: