mirror of https://github.com/ArduPilot/ardupilot
Rover: move rssi.init and set_control_channels
This commit is contained in:
parent
7595ffb8ba
commit
feb8c30af4
|
@ -105,8 +105,6 @@ void Rover::setup()
|
|||
|
||||
in_auto_reverse = false;
|
||||
|
||||
rssi.init();
|
||||
|
||||
init_ardupilot();
|
||||
|
||||
// initialise the main loop scheduler
|
||||
|
|
|
@ -115,10 +115,10 @@ void Rover::init_ardupilot()
|
|||
|
||||
ServoRelayEvents.set_channel_mask(0xFFF0);
|
||||
|
||||
set_control_channels();
|
||||
|
||||
battery.init();
|
||||
|
||||
rssi.init();
|
||||
|
||||
// keep a record of how many resets have happened. This can be
|
||||
// used to detect in-flight resets
|
||||
g.num_resets.set_and_save(g.num_resets+1);
|
||||
|
@ -165,6 +165,7 @@ void Rover::init_ardupilot()
|
|||
|
||||
rc_override_active = hal.rcin->set_overrides(rc_override, 8);
|
||||
|
||||
set_control_channels();
|
||||
init_rc_in(); // sets up rc channels from radio
|
||||
init_rc_out(); // sets up the timer libs
|
||||
|
||||
|
@ -420,6 +421,7 @@ void Rover::startup_INS_ground(void)
|
|||
mavlink_delay(1000);
|
||||
|
||||
ahrs.init();
|
||||
// say to EKF that rover only move by goind forward
|
||||
ahrs.set_fly_forward(true);
|
||||
ahrs.set_vehicle_class(AHRS_VEHICLE_GROUND);
|
||||
|
||||
|
|
Loading…
Reference in New Issue