From 53fc095d4ce6ac0783acfb7394d3187502a43530 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 May 2016 15:05:52 +1000 Subject: [PATCH] Copter: fixed motor test build on heli pwm percent makes no sense --- ArduCopter/motor_test.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index ae34c4b7e2..f71e991a52 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -38,11 +38,13 @@ void Copter::motor_test_output() case MOTOR_TEST_THROTTLE_PERCENT: // sanity check motor_test_throttle value +#if FRAME_CONFIG != HELI_FRAME if (motor_test_throttle_value <= 100) { int16_t pwm_min = motors.get_pwm_output_min(); int16_t pwm_max = motors.get_pwm_output_max(); pwm = pwm_min + (pwm_max - pwm_min) * (float)motor_test_throttle_value/100.0f; } +#endif break; case MOTOR_TEST_THROTTLE_PWM: