mirror of https://github.com/ArduPilot/ardupilot
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:
parent
406a7739a6
commit
54539fc5af
|
@ -6,15 +6,15 @@
|
||||||
|
|
||||||
void Copter::default_dead_zones()
|
void Copter::default_dead_zones()
|
||||||
{
|
{
|
||||||
channel_roll->set_default_dead_zone(10);
|
channel_roll->set_default_dead_zone(20);
|
||||||
channel_pitch->set_default_dead_zone(10);
|
channel_pitch->set_default_dead_zone(20);
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
channel_throttle->set_default_dead_zone(10);
|
channel_throttle->set_default_dead_zone(10);
|
||||||
channel_yaw->set_default_dead_zone(15);
|
channel_yaw->set_default_dead_zone(15);
|
||||||
RC_Channels::rc_channel(CH_6)->set_default_dead_zone(10);
|
RC_Channels::rc_channel(CH_6)->set_default_dead_zone(10);
|
||||||
#else
|
#else
|
||||||
channel_throttle->set_default_dead_zone(30);
|
channel_throttle->set_default_dead_zone(30);
|
||||||
channel_yaw->set_default_dead_zone(10);
|
channel_yaw->set_default_dead_zone(20);
|
||||||
#endif
|
#endif
|
||||||
RC_Channels::rc_channel(CH_6)->set_default_dead_zone(0);
|
RC_Channels::rc_channel(CH_6)->set_default_dead_zone(0);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue