diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index eebb5a23de..8463fa68f2 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -469,6 +469,8 @@ void Copter::one_hz_loop() #if FRAME_CONFIG != HELI_FRAME // set all throttle channel settings motors.set_throttle_range(g.throttle_min, channel_throttle->radio_min, channel_throttle->radio_max); + // set hover throttle + motors.set_hover_throttle(g.throttle_mid); #endif } diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 99e879c46f..ba09a3d30e 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -201,9 +201,6 @@ bool Copter::init_arm_motors(bool arming_from_gcs) ahrs.set_correct_centrifugal(true); hal.util->set_soft_armed(true); - // set hover throttle - motors.set_hover_throttle(g.throttle_mid); - #if SPRAYER == ENABLED // turn off sprayer's test if on sprayer.test_pump(false); diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index d16dd7e8e8..faa517765c 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -59,6 +59,7 @@ void Copter::init_rc_out() motors.Init(); // motor initialisation #if FRAME_CONFIG != HELI_FRAME motors.set_throttle_range(g.throttle_min, channel_throttle->radio_min, channel_throttle->radio_max); + motors.set_hover_throttle(g.throttle_mid); #endif for(uint8_t i = 0; i < 5; i++) {