mirror of https://github.com/ArduPilot/ardupilot
Copter: update_throttle_range don't set_throttle_range
This commit is contained in:
parent
14dfac42e7
commit
f487118ee9
|
@ -564,7 +564,7 @@ void Copter::one_hz_loop()
|
|||
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
// set all throttle channel settings
|
||||
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||
motors->update_throttle_range();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -51,7 +51,7 @@ void Copter::init_rc_out()
|
|||
motors->set_update_rate(g.rc_speed);
|
||||
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||
motors->update_throttle_range();
|
||||
#else
|
||||
// setup correct scaling for ESCs like the UAVCAN ESCs which
|
||||
// take a proportion of speed.
|
||||
|
|
Loading…
Reference in New Issue