Copter: fixed motor test build on heli

pwm percent makes no sense
This commit is contained in:
Andrew Tridgell 2016-05-26 15:05:52 +10:00
parent c605f09859
commit 53fc095d4c
1 changed files with 2 additions and 0 deletions

View File

@ -38,11 +38,13 @@ void Copter::motor_test_output()
case MOTOR_TEST_THROTTLE_PERCENT:
// sanity check motor_test_throttle value
#if FRAME_CONFIG != HELI_FRAME
if (motor_test_throttle_value <= 100) {
int16_t pwm_min = motors.get_pwm_output_min();
int16_t pwm_max = motors.get_pwm_output_max();
pwm = pwm_min + (pwm_max - pwm_min) * (float)motor_test_throttle_value/100.0f;
}
#endif
break;
case MOTOR_TEST_THROTTLE_PWM: