mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
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
This commit is contained in:
parent
47437b9ddf
commit
9df93881fb
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user