From 692d7abf1c1664117a2b4da8fce65361788b8b66 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 16 Jan 2020 21:40:52 +1100 Subject: [PATCH] APMrover2: move some common init_ardupilot code up to AP_Vehicle --- APMrover2/Rover.h | 2 +- APMrover2/system.cpp | 14 -------------- 2 files changed, 1 insertion(+), 15 deletions(-) diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 85f1f56f14..5494c580e8 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -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); diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 85a7569fce..21bec82ea3 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -6,7 +6,6 @@ The init_ardupilot function processes everything we need for an in - air restart *****************************************************************************/ #include "Rover.h" -#include 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();