diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 4629b605bd..c80205d2b3 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -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 diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index a65c316f5c..91791dee54 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -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();