mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: reduce dead zone for roll, pitch and yaw input
This commit is contained in:
parent
53486a5725
commit
0523570c5f
@ -6,15 +6,15 @@
|
||||
|
||||
void Copter::default_dead_zones()
|
||||
{
|
||||
channel_roll->set_default_dead_zone(30);
|
||||
channel_pitch->set_default_dead_zone(30);
|
||||
channel_roll->set_default_dead_zone(10);
|
||||
channel_pitch->set_default_dead_zone(10);
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
channel_throttle->set_default_dead_zone(10);
|
||||
channel_yaw->set_default_dead_zone(15);
|
||||
g.rc_8.set_default_dead_zone(10);
|
||||
#else
|
||||
channel_throttle->set_default_dead_zone(30);
|
||||
channel_yaw->set_default_dead_zone(40);
|
||||
channel_yaw->set_default_dead_zone(10);
|
||||
#endif
|
||||
g.rc_6.set_default_dead_zone(0);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user