Plane: motor_test: use PWM min and max from RC_Channel

This commit is contained in:
Iampete1 2022-02-15 00:35:33 +00:00 committed by Andrew Tridgell
parent 96c47dadcb
commit c26ffed47f

View File

@ -7,8 +7,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_MS_MAX 30000 // max timeout is 30 seconds
// motor_test_output - checks for timeout and sends updates to motors objects
@ -68,7 +66,7 @@ void QuadPlane::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 vlaue
motors->output_test_seq(motor_test.seq, pwm);
} else {