Browse Source

Copter: fixed motor test build on heli

pwm percent makes no sense
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
53fc095d4c
  1. 2
      ArduCopter/motor_test.cpp

2
ArduCopter/motor_test.cpp

@ -38,11 +38,13 @@ void Copter::motor_test_output() @@ -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:

Loading…
Cancel
Save