Copter: call set_throttle_range for multicopters only

This commit is contained in:
Randy Mackay 2015-07-15 14:35:20 +09:00
parent 53aad69fa2
commit 88b617707f
2 changed files with 4 additions and 0 deletions

View File

@ -466,8 +466,10 @@ void Copter::one_hz_loop()
// check the user hasn't updated the frame orientation
motors.set_frame_orientation(g.frame_orientation);
#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);
#endif
}
// update assigned functions and enable auxiliar servos

View File

@ -57,7 +57,9 @@ void Copter::init_rc_out()
motors.set_update_rate(g.rc_speed);
motors.set_frame_orientation(g.frame_orientation);
motors.Init(); // motor initialisation
#if FRAME_CONFIG != HELI_FRAME
motors.set_throttle_range(g.throttle_min, channel_throttle->radio_min, channel_throttle->radio_max);
#endif
for(uint8_t i = 0; i < 5; i++) {
delay(20);