mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Copter: fixed motor test with percentage
use motors min/max pwm, not throttle channel range
This commit is contained in:
parent
65eb9ceb32
commit
c605f09859
@ -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;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user