mirror of https://github.com/ArduPilot/ardupilot
TradHeli - changed deadzones for throttle to zero (and also reduced for yaw)
This commit is contained in:
parent
e3ab1b0353
commit
f1e626e3c1
|
@ -8,8 +8,13 @@ static void default_dead_zones()
|
||||||
{
|
{
|
||||||
g.rc_1.set_dead_zone(60);
|
g.rc_1.set_dead_zone(60);
|
||||||
g.rc_2.set_dead_zone(60);
|
g.rc_2.set_dead_zone(60);
|
||||||
g.rc_3.set_dead_zone(60);
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
g.rc_4.set_dead_zone(200);
|
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()
|
static void init_rc_in()
|
||||||
|
|
Loading…
Reference in New Issue