From 8b3c414ca78838a55e4ec3ad874bb1c20d8d3409 Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Thu, 13 Apr 2017 18:53:48 -0400 Subject: [PATCH] Sub: Remove cliSerial alias for hal.console --- ArduSub/ArduSub.cpp | 2 -- ArduSub/Parameters.cpp | 8 ++++---- ArduSub/Sub.h | 5 ----- ArduSub/sensors.cpp | 2 +- ArduSub/system.cpp | 4 ++-- 5 files changed, 7 insertions(+), 14 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index f52d242b81..c69eca2eee 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -81,8 +81,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { void Sub::setup() { - cliSerial = hal.console; - // Load the default values of variables listed in var_info[]s AP_Param::setup_sketch_defaults(); diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 9e6a719b0f..87ac08380e 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -754,7 +754,7 @@ ParametersG2::ParametersG2(void) void Sub::load_parameters(void) { if (!AP_Param::check_var_info()) { - cliSerial->printf("Bad var table\n"); + hal.console->printf("Bad var table\n"); AP_HAL::panic("Bad var table"); } @@ -766,18 +766,18 @@ void Sub::load_parameters(void) g.format_version != Parameters::k_format_version) { // erase all parameters - cliSerial->printf("Firmware change: erasing EEPROM...\n"); + hal.console->printf("Firmware change: erasing EEPROM...\n"); AP_Param::erase_all(); // save the current format version g.format_version.set_and_save(Parameters::k_format_version); - cliSerial->println("done."); + hal.console->println("done."); } uint32_t before = micros(); // Load all auto-loaded EEPROM variables AP_Param::load_all(); - cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before)); + hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index f1e08fc9c9..c362a04dac 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -135,11 +135,6 @@ private: // key aircraft parameters passed to multiple libraries AP_Vehicle::MultiCopter aparm; - - // cliSerial isn't strictly necessary - it is an alias for hal.console. It may - // be deprecated in favor of hal.console in later releases. - AP_HAL::BetterStream* cliSerial; - // Global parameters are all contained within the 'g' class. Parameters g; ParametersG2 g2; diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index bf4a88d3bc..c599d9e61a 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -95,7 +95,7 @@ void Sub::init_compass() { if (!compass.init() || !compass.read()) { // make sure we don't pass a broken compass to DCM - cliSerial->println("COMPASS INIT ERROR"); + hal.console->println("COMPASS INIT ERROR"); Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE); return; } diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 3c57cd843d..fd03704fe5 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -23,7 +23,7 @@ void Sub::init_ardupilot() // initialise serial port serial_manager.init_console(); - cliSerial->printf("\n\nInit " FIRMWARE_STRING + hal.console->printf("\n\nInit " FIRMWARE_STRING "\n\nFree RAM: %u\n", (unsigned)hal.util->available_memory()); @@ -190,7 +190,7 @@ void Sub::init_ardupilot() // init vehicle capabilties init_capabilities(); - cliSerial->print("\nReady to FLY "); + hal.console->print("\nInit complete"); // flag that initialisation has completed ap.initialised = true;