Plane: init rc output after quadplane setup

this ensures first PWM pulses are correct
This commit is contained in:
Andrew Tridgell 2016-01-05 09:38:02 +11:00
parent 13a71c5cde
commit 0a0e191284
2 changed files with 5 additions and 3 deletions

View File

@ -46,8 +46,6 @@ void Plane::init_rc_in()
channel_pitch->set_default_dead_zone(30);
channel_rudder->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_rudder->enable_out();
update_aux();
RC_Channel_aux::enable_aux_servos();
// Initialization of servo outputs

View File

@ -196,7 +196,6 @@ void Plane::init_ardupilot()
gps.init(&DataFlash, serial_manager);
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up the timer libs
relay.init();
@ -234,6 +233,10 @@ void Plane::init_ardupilot()
startup_ground();
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
set_nav_controller();