diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index fbc9367569..9c2740912c 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -565,7 +565,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 } diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 5a496405df..cfaad26b79 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -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.