mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: update_throttle_range don't set_throttle_range
This commit is contained in:
parent
5684353000
commit
39a71966df
@ -565,7 +565,7 @@ void Copter::one_hz_loop()
|
|||||||
|
|
||||||
#if FRAME_CONFIG != HELI_FRAME
|
#if FRAME_CONFIG != HELI_FRAME
|
||||||
// set all throttle channel settings
|
// set all throttle channel settings
|
||||||
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
motors->update_throttle_range();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -51,7 +51,7 @@ void Copter::init_rc_out()
|
|||||||
motors->set_update_rate(g.rc_speed);
|
motors->set_update_rate(g.rc_speed);
|
||||||
|
|
||||||
#if FRAME_CONFIG != HELI_FRAME
|
#if FRAME_CONFIG != HELI_FRAME
|
||||||
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
motors->update_throttle_range();
|
||||||
#else
|
#else
|
||||||
// setup correct scaling for ESCs like the UAVCAN ESCs which
|
// setup correct scaling for ESCs like the UAVCAN ESCs which
|
||||||
// take a proportion of speed.
|
// take a proportion of speed.
|
||||||
|
Loading…
Reference in New Issue
Block a user