From e96d0f745cebd609f52d1fff19d1e41797323d74 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 15 Jul 2013 10:25:30 +1000 Subject: [PATCH] Rover: fixed dead-zone on throttle --- APMrover2/radio.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/radio.pde b/APMrover2/radio.pde index 56223e6a81..1962249ed4 100644 --- a/APMrover2/radio.pde +++ b/APMrover2/radio.pde @@ -18,7 +18,7 @@ static void init_rc_in() { // set rc dead zones channel_steer->set_default_dead_zone(30); - channel_throttle->set_default_dead_zone(3); + channel_throttle->set_default_dead_zone(30); //set auxiliary ranges update_aux();