From 54539fc5af1172b3882f8ed2b1587c9cffc816dd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 1 Jun 2017 10:10:57 +0900 Subject: [PATCH] Copter: increase RC input deadzones for roll pitch and yaw Copter-3.5 testing resulted in a significant number of users reporting various issues like poshold and autotune were not functioning because their RC inputs were straying out of the deadzones --- ArduCopter/radio.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 1d7fba2320..589c16d572 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -6,15 +6,15 @@ void Copter::default_dead_zones() { - channel_roll->set_default_dead_zone(10); - channel_pitch->set_default_dead_zone(10); + channel_roll->set_default_dead_zone(20); + channel_pitch->set_default_dead_zone(20); #if FRAME_CONFIG == HELI_FRAME channel_throttle->set_default_dead_zone(10); channel_yaw->set_default_dead_zone(15); RC_Channels::rc_channel(CH_6)->set_default_dead_zone(10); #else channel_throttle->set_default_dead_zone(30); - channel_yaw->set_default_dead_zone(10); + channel_yaw->set_default_dead_zone(20); #endif RC_Channels::rc_channel(CH_6)->set_default_dead_zone(0); }