From 0f67e25d3794ff636db474564369dc980598769e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 10 Nov 2013 20:29:26 +0900 Subject: [PATCH] TradHeli: set throttle_min to zero by default --- ArduCopter/config.h | 1 + ArduCopter/radio.pde | 5 ----- 2 files changed, 1 insertion(+), 5 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index a2726160b7..9719cd5251 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -115,6 +115,7 @@ # define MPU6K_FILTER 10 # define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0 # define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000 + # define THR_MIN_DEFAULT 0 #endif ///////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 3c2368c020..e40c15417c 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -23,12 +23,7 @@ static void init_rc_in() // set rc channel ranges g.rc_1.set_angle(ROLL_PITCH_INPUT_MAX); g.rc_2.set_angle(ROLL_PITCH_INPUT_MAX); -#if FRAME_CONFIG == HELI_FRAME - // we do not want to limit the movment of the heli's swash plate - g.rc_3.set_range(0, 1000); -#else g.rc_3.set_range(g.throttle_min, g.throttle_max); -#endif g.rc_4.set_angle(4500); g.rc_1.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);