Browse Source

APMrover2: move some common init_ardupilot code up to AP_Vehicle

zr-v5.1
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
692d7abf1c
  1. 2
      APMrover2/Rover.h
  2. 14
      APMrover2/system.cpp

2
APMrover2/Rover.h

@ -361,7 +361,7 @@ private: @@ -361,7 +361,7 @@ private:
Mode *mode_from_mode_num(enum Mode::Number num);
// Parameters.cpp
void load_parameters(void);
void load_parameters(void) override;
// radio.cpp
void set_control_channels(void);

14
APMrover2/system.cpp

@ -6,7 +6,6 @@ The init_ardupilot function processes everything we need for an in - air restart @@ -6,7 +6,6 @@ The init_ardupilot function processes everything we need for an in - air restart
*****************************************************************************/
#include "Rover.h"
#include <AP_Common/AP_FWVersion.h>
static void failsafe_check_static()
{
@ -15,19 +14,6 @@ static void failsafe_check_static() @@ -15,19 +14,6 @@ static void failsafe_check_static()
void Rover::init_ardupilot()
{
// initialise console serial port
serial_manager.init_console();
hal.console->printf("\n\nInit %s"
"\n\nFree RAM: %u\n",
AP::fwversion().fw_string,
(unsigned)hal.util->available_memory());
//
// Check the EEPROM format version before loading any parameters from EEPROM.
//
load_parameters();
#if STATS_ENABLED == ENABLED
// initialise stats module
g2.stats.init();

Loading…
Cancel
Save