mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Sub: Remove cliSerial alias for hal.console
This commit is contained in:
parent
6008689aa3
commit
8b3c414ca7
@ -81,8 +81,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||||||
|
|
||||||
void Sub::setup()
|
void Sub::setup()
|
||||||
{
|
{
|
||||||
cliSerial = hal.console;
|
|
||||||
|
|
||||||
// Load the default values of variables listed in var_info[]s
|
// Load the default values of variables listed in var_info[]s
|
||||||
AP_Param::setup_sketch_defaults();
|
AP_Param::setup_sketch_defaults();
|
||||||
|
|
||||||
|
@ -754,7 +754,7 @@ ParametersG2::ParametersG2(void)
|
|||||||
void Sub::load_parameters(void)
|
void Sub::load_parameters(void)
|
||||||
{
|
{
|
||||||
if (!AP_Param::check_var_info()) {
|
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");
|
AP_HAL::panic("Bad var table");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -766,18 +766,18 @@ void Sub::load_parameters(void)
|
|||||||
g.format_version != Parameters::k_format_version) {
|
g.format_version != Parameters::k_format_version) {
|
||||||
|
|
||||||
// erase all parameters
|
// erase all parameters
|
||||||
cliSerial->printf("Firmware change: erasing EEPROM...\n");
|
hal.console->printf("Firmware change: erasing EEPROM...\n");
|
||||||
AP_Param::erase_all();
|
AP_Param::erase_all();
|
||||||
|
|
||||||
// save the current format version
|
// save the current format version
|
||||||
g.format_version.set_and_save(Parameters::k_format_version);
|
g.format_version.set_and_save(Parameters::k_format_version);
|
||||||
cliSerial->println("done.");
|
hal.console->println("done.");
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t before = micros();
|
uint32_t before = micros();
|
||||||
// Load all auto-loaded EEPROM variables
|
// Load all auto-loaded EEPROM variables
|
||||||
AP_Param::load_all();
|
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);
|
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB);
|
||||||
|
|
||||||
|
@ -135,11 +135,6 @@ private:
|
|||||||
// key aircraft parameters passed to multiple libraries
|
// key aircraft parameters passed to multiple libraries
|
||||||
AP_Vehicle::MultiCopter aparm;
|
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.
|
// Global parameters are all contained within the 'g' class.
|
||||||
Parameters g;
|
Parameters g;
|
||||||
ParametersG2 g2;
|
ParametersG2 g2;
|
||||||
|
@ -95,7 +95,7 @@ void Sub::init_compass()
|
|||||||
{
|
{
|
||||||
if (!compass.init() || !compass.read()) {
|
if (!compass.init() || !compass.read()) {
|
||||||
// make sure we don't pass a broken compass to DCM
|
// 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);
|
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -23,7 +23,7 @@ void Sub::init_ardupilot()
|
|||||||
// initialise serial port
|
// initialise serial port
|
||||||
serial_manager.init_console();
|
serial_manager.init_console();
|
||||||
|
|
||||||
cliSerial->printf("\n\nInit " FIRMWARE_STRING
|
hal.console->printf("\n\nInit " FIRMWARE_STRING
|
||||||
"\n\nFree RAM: %u\n",
|
"\n\nFree RAM: %u\n",
|
||||||
(unsigned)hal.util->available_memory());
|
(unsigned)hal.util->available_memory());
|
||||||
|
|
||||||
@ -190,7 +190,7 @@ void Sub::init_ardupilot()
|
|||||||
// init vehicle capabilties
|
// init vehicle capabilties
|
||||||
init_capabilities();
|
init_capabilities();
|
||||||
|
|
||||||
cliSerial->print("\nReady to FLY ");
|
hal.console->print("\nInit complete");
|
||||||
|
|
||||||
// flag that initialisation has completed
|
// flag that initialisation has completed
|
||||||
ap.initialised = true;
|
ap.initialised = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user