mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: fixed default deadzone for the throttle channel
this is the 2nd half of the fix for issue #303
This commit is contained in:
parent
21859f9364
commit
399970e76f
@ -30,7 +30,7 @@ static void init_rc_in()
|
|||||||
channel_roll->set_default_dead_zone(30);
|
channel_roll->set_default_dead_zone(30);
|
||||||
channel_pitch->set_default_dead_zone(30);
|
channel_pitch->set_default_dead_zone(30);
|
||||||
channel_rudder->set_default_dead_zone(30);
|
channel_rudder->set_default_dead_zone(30);
|
||||||
channel_throttle->set_default_dead_zone(3);
|
channel_throttle->set_default_dead_zone(30);
|
||||||
|
|
||||||
//set auxiliary ranges
|
//set auxiliary ranges
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
|
Loading…
Reference in New Issue
Block a user