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
This commit is contained in:
Randy Mackay 2017-06-01 10:10:57 +09:00
parent ad74769fb7
commit 010dc103be
1 changed files with 3 additions and 3 deletions

View File

@ -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);
}