From 96c47dadcbdfbdea4cb744390a36940026580fda Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 15 Feb 2022 00:35:23 +0000 Subject: [PATCH] Copter: motor_test: use PWM min and max from RC_Channel --- ArduCopter/motor_test.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 2248aa3e16..b222e24f49 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -6,8 +6,6 @@ */ // motor test definitions -#define MOTOR_TEST_PWM_MIN 800 // min pwm value accepted by the test -#define MOTOR_TEST_PWM_MAX 2200 // max pwm value accepted by the test #define MOTOR_TEST_TIMEOUT_SEC 600 // max timeout is 10 minutes (600 seconds) static uint32_t motor_test_start_ms; // system time the motor test began @@ -84,7 +82,7 @@ void Copter::motor_test_output() } // sanity check throttle values - if (pwm >= MOTOR_TEST_PWM_MIN && pwm <= MOTOR_TEST_PWM_MAX ) { + if (pwm >= RC_Channel::RC_MIN_LIMIT_PWM && pwm <= RC_Channel::RC_MAX_LIMIT_PWM) { // turn on motor to specified pwm value motors->output_test_seq(motor_test_seq, pwm); } else {