mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Plane: set min quad throttle to 10%
fixes spin when armed
This commit is contained in:
parent
7f85c14c96
commit
913cf9dd37
@ -333,7 +333,7 @@ bool QuadPlane::setup(void)
|
||||
|
||||
motors->set_frame_orientation(frame_type);
|
||||
motors->Init();
|
||||
motors->set_throttle_range(0, thr_min_pwm, thr_max_pwm);
|
||||
motors->set_throttle_range(100, thr_min_pwm, thr_max_pwm);
|
||||
motors->set_hover_throttle(throttle_mid);
|
||||
motors->set_update_rate(rc_speed);
|
||||
motors->set_interlock(true);
|
||||
|
Loading…
Reference in New Issue
Block a user