mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: reoder rc and servo init
This commit is contained in:
parent
7473471f38
commit
b28656eb11
@ -32,14 +32,14 @@ void Rover::init_rc_in()
|
|||||||
// set rc dead zones
|
// set rc dead zones
|
||||||
channel_steer->set_default_dead_zone(30);
|
channel_steer->set_default_dead_zone(30);
|
||||||
channel_throttle->set_default_dead_zone(30);
|
channel_throttle->set_default_dead_zone(30);
|
||||||
|
|
||||||
// set auxiliary ranges
|
|
||||||
update_aux();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::init_rc_out()
|
void Rover::init_rc_out()
|
||||||
{
|
{
|
||||||
SRV_Channels::output_trim_all();
|
SRV_Channels::output_trim_all();
|
||||||
|
|
||||||
|
// set auxiliary ranges
|
||||||
|
update_aux();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -176,12 +176,10 @@ void Rover::init_ardupilot()
|
|||||||
|
|
||||||
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
||||||
|
|
||||||
set_control_channels();
|
set_control_channels(); // setup radio channels and ouputs ranges
|
||||||
init_rc_in(); // sets up rc channels from radio
|
init_rc_in(); // sets up rc channels deadzone
|
||||||
init_rc_out(); // sets up the timer libs
|
g2.motors.init(); // init motors including setting servo out channels ranges
|
||||||
|
init_rc_out(); // enable output
|
||||||
// init motors including setting rc out channels ranges
|
|
||||||
g2.motors.init();
|
|
||||||
|
|
||||||
relay.init();
|
relay.init();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user