Copter: fixed motor test with percentage

use motors min/max pwm, not throttle channel range
This commit is contained in:
Andrew Tridgell 2016-05-26 14:34:27 +10:00
parent 65eb9ceb32
commit c605f09859

View File

@ -39,9 +39,9 @@ void Copter::motor_test_output()
case MOTOR_TEST_THROTTLE_PERCENT: case MOTOR_TEST_THROTTLE_PERCENT:
// sanity check motor_test_throttle value // sanity check motor_test_throttle value
if (motor_test_throttle_value <= 100) { if (motor_test_throttle_value <= 100) {
pwm = channel_throttle->get_radio_min() int16_t pwm_min = motors.get_pwm_output_min();
+ (channel_throttle->get_radio_max() - channel_throttle->get_radio_min()) int16_t pwm_max = motors.get_pwm_output_max();
* (float)motor_test_throttle_value/100.0f; pwm = pwm_min + (pwm_max - pwm_min) * (float)motor_test_throttle_value/100.0f;
} }
break; break;