From 9df93881fbb00194df8ac9526fd0477380096ac9 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 11 Jul 2013 23:12:26 +0900 Subject: [PATCH] Plane: set_dead_zone renamed to set_default_dead_zone Change in use of parameter means value passed in should be 1/2 what it was previously --- ArduPlane/radio.pde | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 8549ea60bd..e287e74770 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -27,15 +27,10 @@ static void set_control_channels(void) static void init_rc_in() { // set rc dead zones - channel_roll->set_dead_zone(60); - channel_pitch->set_dead_zone(60); - channel_rudder->set_dead_zone(60); - channel_throttle->set_dead_zone(6); - - //channel_roll->dead_zone = 60; - //channel_pitch->dead_zone = 60; - //channel_rudder->dead_zone = 60; - //channel_throttle->dead_zone = 6; + 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); //set auxiliary ranges #if CONFIG_HAL_BOARD == HAL_BOARD_PX4