diff --git a/ArduPlane/motor_test.cpp b/ArduPlane/motor_test.cpp index db8f137a00..b8f3f60a05 100644 --- a/ArduPlane/motor_test.cpp +++ b/ArduPlane/motor_test.cpp @@ -66,7 +66,7 @@ void QuadPlane::motor_test_output() // sanity check throttle values if (pwm >= MOTOR_TEST_PWM_MIN && pwm <= MOTOR_TEST_PWM_MAX ) { // turn on motor to specified pwm vlaue - motors->output_test(motor_test.seq, pwm); + motors->output_test_seq(motor_test.seq, pwm); } else { motor_test_stop(); }