diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 6580c0d913..8d673e5778 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -32,14 +32,14 @@ void Rover::init_rc_in() // set rc dead zones channel_steer->set_default_dead_zone(30); channel_throttle->set_default_dead_zone(30); - - // set auxiliary ranges - update_aux(); } void Rover::init_rc_out() { SRV_Channels::output_trim_all(); + + // set auxiliary ranges + update_aux(); } /* diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 20a5b59166..5628000d0b 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -176,12 +176,10 @@ void Rover::init_ardupilot() ins.set_log_raw_bit(MASK_LOG_IMU_RAW); - set_control_channels(); - init_rc_in(); // sets up rc channels from radio - init_rc_out(); // sets up the timer libs - - // init motors including setting rc out channels ranges - g2.motors.init(); + set_control_channels(); // setup radio channels and ouputs ranges + init_rc_in(); // sets up rc channels deadzone + g2.motors.init(); // init motors including setting servo out channels ranges + init_rc_out(); // enable output relay.init();