Rover: reoder rc and servo init

This commit is contained in:
khancyr 2017-07-10 11:43:55 +02:00 committed by Randy Mackay
parent 7473471f38
commit b28656eb11
2 changed files with 7 additions and 9 deletions

View File

@ -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();
}
/*

View File

@ -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();