Plane: fixed default deadzone for the throttle channel

this is the 2nd half of the fix for issue #303
This commit is contained in:
Andrew Tridgell 2013-07-13 13:19:25 +10:00
parent 21859f9364
commit 399970e76f
1 changed files with 1 additions and 1 deletions

View File

@ -30,7 +30,7 @@ static void init_rc_in()
channel_roll->set_default_dead_zone(30);
channel_pitch->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
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4