From 9933069679caf5b6e77018093d780707e45130d4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 27 May 2016 11:53:08 +1000 Subject: [PATCH] Plane: fixed motor test by percentage in quadplane --- ArduPlane/motor_test.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/motor_test.cpp b/ArduPlane/motor_test.cpp index 8c4d88fa25..98b019a4e4 100644 --- a/ArduPlane/motor_test.cpp +++ b/ArduPlane/motor_test.cpp @@ -48,7 +48,7 @@ void QuadPlane::motor_test_output() case MOTOR_TEST_THROTTLE_PERCENT: // sanity check motor_test.throttle value if (motor_test.throttle_value <= 100) { - pwm = plane.channel_throttle->get_radio_min() + (plane.channel_throttle->get_radio_max() - plane.channel_throttle->get_radio_min()) * (float)motor_test.throttle_value/100.0f; + pwm = thr_min_pwm + (thr_max_pwm - thr_min_pwm) * (float)motor_test.throttle_value*0.01f; } break;