mirror of https://github.com/ArduPilot/ardupilot
Plane: update_throttle_range dont set_throttle_range
This commit is contained in:
parent
44c5153df8
commit
d1d6342165
|
@ -672,7 +672,7 @@ bool QuadPlane::setup(void)
|
|||
AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info);
|
||||
|
||||
motors->init(frame_class, frame_type);
|
||||
motors->set_throttle_range(thr_min_pwm, thr_max_pwm);
|
||||
motors->update_throttle_range();
|
||||
motors->set_update_rate(rc_speed);
|
||||
motors->set_interlock(true);
|
||||
attitude_control->parameter_sanity_check();
|
||||
|
|
Loading…
Reference in New Issue