Browse Source

Rover: move rssi.init and set_control_channels

master
Pierre Kancir 8 years ago committed by Randy Mackay
parent
commit
feb8c30af4
  1. 2
      APMrover2/APMrover2.cpp
  2. 6
      APMrover2/system.cpp

2
APMrover2/APMrover2.cpp

@ -105,8 +105,6 @@ void Rover::setup() @@ -105,8 +105,6 @@ void Rover::setup()
in_auto_reverse = false;
rssi.init();
init_ardupilot();
// initialise the main loop scheduler

6
APMrover2/system.cpp

@ -115,10 +115,10 @@ void Rover::init_ardupilot() @@ -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() @@ -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) @@ -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…
Cancel
Save