Copter: no set_hover_throttle for TradHeli

This commit is contained in:
Randy Mackay 2015-07-15 15:03:14 +09:00
parent 88b617707f
commit 546d668d1d
3 changed files with 3 additions and 3 deletions

View File

@ -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
}

View File

@ -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);

View File

@ -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++) {