From f1e626e3c14f9b4a822480e84940abf78be749c8 Mon Sep 17 00:00:00 2001 From: unknown Date: Sun, 6 Nov 2011 17:37:59 +0800 Subject: [PATCH] TradHeli - changed deadzones for throttle to zero (and also reduced for yaw) --- ArduCopter/radio.pde | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index cf5abebca0..f0b3d11d7a 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -8,8 +8,13 @@ static void default_dead_zones() { g.rc_1.set_dead_zone(60); g.rc_2.set_dead_zone(60); - g.rc_3.set_dead_zone(60); - g.rc_4.set_dead_zone(200); + #if FRAME_CONFIG == HELI_FRAME + g.rc_3.set_dead_zone(0); + g.rc_4.set_dead_zone(60); + #else + g.rc_3.set_dead_zone(60); + g.rc_4.set_dead_zone(200); + #endif } static void init_rc_in()