mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed pilot throttle based motor test
This commit is contained in:
parent
d89b82b69f
commit
08dc5fab12
|
@ -57,7 +57,7 @@ void QuadPlane::motor_test_output()
|
|||
break;
|
||||
|
||||
case MOTOR_TEST_THROTTLE_PILOT:
|
||||
pwm = plane.channel_throttle->get_radio_in();
|
||||
pwm = thr_min_pwm + (thr_max_pwm - thr_min_pwm) * (float)plane.channel_throttle->get_control_in()*0.01f;
|
||||
break;
|
||||
|
||||
default:
|
||||
|
|
Loading…
Reference in New Issue