mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: init rc output after quadplane setup
this ensures first PWM pulses are correct
This commit is contained in:
parent
13a71c5cde
commit
0a0e191284
@ -46,8 +46,6 @@ void Plane::init_rc_in()
|
|||||||
channel_pitch->set_default_dead_zone(30);
|
channel_pitch->set_default_dead_zone(30);
|
||||||
channel_rudder->set_default_dead_zone(30);
|
channel_rudder->set_default_dead_zone(30);
|
||||||
channel_throttle->set_default_dead_zone(30);
|
channel_throttle->set_default_dead_zone(30);
|
||||||
|
|
||||||
update_aux();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -69,6 +67,7 @@ void Plane::init_rc_out()
|
|||||||
channel_throttle->enable_out();
|
channel_throttle->enable_out();
|
||||||
}
|
}
|
||||||
channel_rudder->enable_out();
|
channel_rudder->enable_out();
|
||||||
|
update_aux();
|
||||||
RC_Channel_aux::enable_aux_servos();
|
RC_Channel_aux::enable_aux_servos();
|
||||||
|
|
||||||
// Initialization of servo outputs
|
// Initialization of servo outputs
|
||||||
|
@ -196,7 +196,6 @@ void Plane::init_ardupilot()
|
|||||||
gps.init(&DataFlash, serial_manager);
|
gps.init(&DataFlash, serial_manager);
|
||||||
|
|
||||||
init_rc_in(); // sets up rc channels from radio
|
init_rc_in(); // sets up rc channels from radio
|
||||||
init_rc_out(); // sets up the timer libs
|
|
||||||
|
|
||||||
relay.init();
|
relay.init();
|
||||||
|
|
||||||
@ -234,6 +233,10 @@ void Plane::init_ardupilot()
|
|||||||
startup_ground();
|
startup_ground();
|
||||||
|
|
||||||
quadplane.setup();
|
quadplane.setup();
|
||||||
|
|
||||||
|
// don't initialise rc output until after quadplane is setup as
|
||||||
|
// that can change initial values of channels
|
||||||
|
init_rc_out();
|
||||||
|
|
||||||
// choose the nav controller
|
// choose the nav controller
|
||||||
set_nav_controller();
|
set_nav_controller();
|
||||||
|
Loading…
Reference in New Issue
Block a user