mirror of https://github.com/ArduPilot/ardupilot
Rover: fixed dead-zone on throttle
This commit is contained in:
parent
8c7619a837
commit
e96d0f745c
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue