From 88b617707fe718dc4cd8fd4a8f065b291974ed23 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 15 Jul 2015 14:35:20 +0900 Subject: [PATCH] Copter: call set_throttle_range for multicopters only --- ArduCopter/ArduCopter.cpp | 2 ++ ArduCopter/radio.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index d119d4a632..eebb5a23de 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -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 diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 043a794c5b..d16dd7e8e8 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -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);