Browse Source

Copter: motor_test: use PWM min and max from RC_Channel

apm_2208
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
96c47dadcb
  1. 4
      ArduCopter/motor_test.cpp

4
ArduCopter/motor_test.cpp

@ -6,8 +6,6 @@ @@ -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() @@ -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 {

Loading…
Cancel
Save