From 8f926bd17793353002b49bf3b183f6eda422045f Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 21 Jan 2017 13:34:19 +0900 Subject: [PATCH] Copter: Unify from print or println to printf. --- ArduCopter/Log.cpp | 14 +++++------ ArduCopter/Parameters.cpp | 6 ++--- ArduCopter/flight_mode.cpp | 36 +++++++++++++-------------- ArduCopter/sensors.cpp | 2 +- ArduCopter/setup.cpp | 50 +++++++++++++++++++------------------- ArduCopter/system.cpp | 8 +++--- ArduCopter/test.cpp | 20 +++++++-------- 7 files changed, 68 insertions(+), 68 deletions(-) diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index d38f926b61..0fd08b98bc 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -24,10 +24,10 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&copter, &Copter::print_l bool Copter::print_log_menu(void) { - cliSerial->print("logs enabled: "); + cliSerial->printf("logs enabled: "); if (0 == g.log_bitmask) { - cliSerial->print("none"); + cliSerial->printf("none"); }else{ // Macro to make the following code a bit easier on the eye. // Pass it the capitalised name of the log option, as defined @@ -52,7 +52,7 @@ bool Copter::print_log_menu(void) #undef PLOG } - cliSerial->println(); + cliSerial->printf("\n"); DataFlash.ListAvailableLogs(cliSerial); @@ -73,11 +73,11 @@ int8_t Copter::dump_log(uint8_t argc, const Menu::arg *argv) DataFlash.DumpPageInfo(cliSerial); return(-1); } else if (dump_log_num <= 0) { - cliSerial->println("dumping all"); + cliSerial->printf("dumping all\n"); Log_Read(0, 1, 0); return(-1); } else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) { - cliSerial->println("bad log number"); + cliSerial->printf("bad log number\n"); return(-1); } @@ -100,7 +100,7 @@ int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv) uint16_t bits; if (argc != 2) { - cliSerial->println("missing log type"); + cliSerial->printf("missing log type\n"); return(-1); } @@ -908,7 +908,7 @@ void Copter::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_pag (unsigned) hal.util->available_memory(), get_frame_string()); - cliSerial->println(HAL_BOARD_NAME); + cliSerial->printf("%s\n", HAL_BOARD_NAME); DataFlash.LogReadProcess(list_entry, start_page, end_page, FUNCTOR_BIND_MEMBER(&Copter::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t), diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 71c9849ba7..47c8b240e2 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1046,7 +1046,7 @@ const AP_Param::ConversionInfo conversion_table[] = { void Copter::load_parameters(void) { if (!AP_Param::check_var_info()) { - cliSerial->println("Bad var table"); + cliSerial->printf("Bad var table\n"); AP_HAL::panic("Bad var table"); } @@ -1058,12 +1058,12 @@ void Copter::load_parameters(void) g.format_version != Parameters::k_format_version) { // erase all parameters - cliSerial->println("Firmware change: erasing EEPROM..."); + cliSerial->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."); + cliSerial->printf("done.\n"); } uint32_t before = micros(); diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 3b8c795df4..84977d417e 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -432,58 +432,58 @@ void Copter::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) { switch (mode) { case STABILIZE: - port->print("STABILIZE"); + port->printf("STABILIZE"); break; case ACRO: - port->print("ACRO"); + port->printf("ACRO"); break; case ALT_HOLD: - port->print("ALT_HOLD"); + port->printf("ALT_HOLD"); break; case AUTO: - port->print("AUTO"); + port->printf("AUTO"); break; case GUIDED: - port->print("GUIDED"); + port->printf("GUIDED"); break; case LOITER: - port->print("LOITER"); + port->printf("LOITER"); break; case RTL: - port->print("RTL"); + port->printf("RTL"); break; case CIRCLE: - port->print("CIRCLE"); + port->printf("CIRCLE"); break; case LAND: - port->print("LAND"); + port->printf("LAND"); break; case DRIFT: - port->print("DRIFT"); + port->printf("DRIFT"); break; case SPORT: - port->print("SPORT"); + port->printf("SPORT"); break; case FLIP: - port->print("FLIP"); + port->printf("FLIP"); break; case AUTOTUNE: - port->print("AUTOTUNE"); + port->printf("AUTOTUNE"); break; case POSHOLD: - port->print("POSHOLD"); + port->printf("POSHOLD"); break; case BRAKE: - port->print("BRAKE"); + port->printf("BRAKE"); break; case THROW: - port->print("THROW"); + port->printf("THROW"); break; case AVOID_ADSB: - port->print("AVOID_ADSB"); + port->printf("AVOID_ADSB"); break; case GUIDED_NOGPS: - port->print("GUIDED_NOGPS"); + port->printf("GUIDED_NOGPS"); break; default: port->printf("Mode(%u)", (unsigned)mode); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 67503eb688..3cfc2f5a29 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -102,7 +102,7 @@ void Copter::init_compass() { if (!compass.init() || !compass.read()) { // make sure we don't pass a broken compass to DCM - cliSerial->println("COMPASS INIT ERROR"); + cliSerial->printf("COMPASS INIT ERROR\n"); Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE); return; } diff --git a/ArduCopter/setup.cpp b/ArduCopter/setup.cpp index 0f9b1266a1..56761bb7c4 100644 --- a/ArduCopter/setup.cpp +++ b/ArduCopter/setup.cpp @@ -69,7 +69,7 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv) if(argc!=3) { - cliSerial->println("Invalid command. Usage: set "); + cliSerial->printf("Invalid command. Usage: set \n"); return 0; } @@ -178,7 +178,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv) set_mask = strtol (argv[1].str, nullptr, 2); if (set_mask == 0) - cliSerial->print("no channels chosen"); + cliSerial->printf("no channels chosen"); //cliSerial->printf("\n%d\n",set_mask); set_mask<<=1; /* wait 50 ms */ @@ -224,7 +224,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv) motors->armed(true); - cliSerial->println("Outputs armed"); + cliSerial->printf("Outputs armed\n"); /* wait for user confirmation */ @@ -286,7 +286,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv) /* disarm */ motors->armed(false); - cliSerial->println("Outputs disarmed"); + cliSerial->printf("Outputs disarmed\n"); cliSerial->printf("%s finished\n", strEscCalib); @@ -305,25 +305,25 @@ void Copter::report_batt_monitor() if (battery.num_instances() == 0) { print_enabled(false); } else if (!battery.has_current()) { - cliSerial->print("volts"); + cliSerial->printf("volts"); } else { - cliSerial->print("volts and cur"); + cliSerial->printf("volts and cur"); } print_blanks(2); } void Copter::report_frame() { - cliSerial->println("Frame"); + cliSerial->printf("Frame\n"); print_divider(); - cliSerial->println(get_frame_string()); + cliSerial->printf("%s\n", get_frame_string()); print_blanks(2); } void Copter::report_radio() { - cliSerial->println("Radio"); + cliSerial->printf("Radio\n"); print_divider(); // radio print_radio_values(); @@ -332,7 +332,7 @@ void Copter::report_radio() void Copter::report_ins() { - cliSerial->println("INS"); + cliSerial->printf("INS\n"); print_divider(); print_gyro_offsets(); @@ -342,7 +342,7 @@ void Copter::report_ins() void Copter::report_flight_modes() { - cliSerial->println("Flight modes"); + cliSerial->printf("Flight modes\n"); print_divider(); for(int16_t i = 0; i < 6; i++ ) { @@ -354,7 +354,7 @@ void Copter::report_flight_modes() void Copter::report_optflow() { #if OPTFLOW == ENABLED - cliSerial->println("OptFlow"); + cliSerial->printf("OptFlow\n"); print_divider(); print_enabled(optflow.enabled()); @@ -381,9 +381,9 @@ void Copter::print_switch(uint8_t p, uint8_t m, bool b) print_flight_mode(cliSerial, m); cliSerial->printf(",\t\tSimple: "); if(b) - cliSerial->println("ON"); + cliSerial->printf("ON\n"); else - cliSerial->println("OFF"); + cliSerial->printf("OFF\n"); } void Copter::print_accel_offsets_and_scaling(void) @@ -413,7 +413,7 @@ void Copter::print_gyro_offsets(void) // report_compass - displays compass information. Also called by compassmot.pde void Copter::report_compass() { - cliSerial->println("Compass"); + cliSerial->printf("Compass\n"); print_divider(); print_enabled(g.compass_enabled); @@ -435,15 +435,15 @@ void Copter::report_compass() } // motor compensation - cliSerial->print("Motor Comp: "); + cliSerial->printf("Motor Comp: "); if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) { - cliSerial->println("Off"); + cliSerial->printf("Off\n"); }else{ if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) { - cliSerial->print("Throttle"); + cliSerial->printf("Throttle"); } if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_CURRENT ) { - cliSerial->print("Current"); + cliSerial->printf("Current"); } Vector3f motor_compensation; for (uint8_t i=0; i 0) { num--; - cliSerial->println(""); + cliSerial->printf("\n"); } } void Copter::print_divider(void) { for (int i = 0; i < 40; i++) { - cliSerial->print("-"); + cliSerial->printf("-"); } - cliSerial->println(); + cliSerial->printf("\n"); } void Copter::print_enabled(bool b) { if(b) - cliSerial->print("en"); + cliSerial->printf("en"); else - cliSerial->print("dis"); - cliSerial->println("abled"); + cliSerial->printf("dis"); + cliSerial->printf("abled\n"); } void Copter::report_version() diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 1652032ab2..dc7995b2fe 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -244,12 +244,12 @@ void Copter::init_ardupilot() #if CLI_ENABLED == ENABLED if (g.cli_enabled) { const char *msg = "\nPress ENTER 3 times to start interactive setup\n"; - cliSerial->println(msg); + cliSerial->printf("%s\n", msg); if (gcs[1].initialised && (gcs[1].get_uart() != nullptr)) { - gcs[1].get_uart()->println(msg); + gcs[1].get_uart()->printf("%s\n", msg); } if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != nullptr)) { - gcs[2].get_uart()->println(msg); + gcs[2].get_uart()->printf("%s\n", msg); } } #endif // CLI_ENABLED @@ -307,7 +307,7 @@ void Copter::init_ardupilot() ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_dataflash(&DataFlash); - cliSerial->print("\nReady to FLY "); + cliSerial->printf("\nReady to FLY "); // flag that initialisation has completed ap.initialised = true; diff --git a/ArduCopter/test.cpp b/ArduCopter/test.cpp index c034c2b4de..31db5b9ba6 100644 --- a/ArduCopter/test.cpp +++ b/ArduCopter/test.cpp @@ -42,7 +42,7 @@ int8_t Copter::test_baro(uint8_t argc, const Menu::arg *argv) read_barometer(); if (!barometer.healthy()) { - cliSerial->println("not healthy"); + cliSerial->printf("not healthy\n"); } else { cliSerial->printf("Alt: %0.2fm, Raw: %f Temperature: %.1f\n", (double)(baro_alt / 100.0f), @@ -63,13 +63,13 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv) uint8_t medium_loopCounter = 0; if (!g.compass_enabled) { - cliSerial->print("Compass: "); + cliSerial->printf("Compass: "); print_enabled(false); return (0); } if (!compass.init()) { - cliSerial->println("Compass initialisation failed!"); + cliSerial->printf("Compass initialisation failed!\n"); return 0; } @@ -125,7 +125,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv) (double)mag_ofs.y, (double)mag_ofs.z); } else { - cliSerial->println("compass not healthy"); + cliSerial->printf("compass not healthy\n"); } counter=0; } @@ -137,7 +137,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv) // save offsets. This allows you to get sane offset values using // the CLI before you go flying. - cliSerial->println("saving offsets"); + cliSerial->printf("saving offsets\n"); compass.save_offsets(); return (0); } @@ -146,12 +146,12 @@ int8_t Copter::test_ins(uint8_t argc, const Menu::arg *argv) { Vector3f gyro, accel; print_hit_enter(); - cliSerial->println("INS"); + cliSerial->printf("INS\n"); delay(1000); ahrs.init(); ins.init(scheduler.get_loop_rate_hz()); - cliSerial->println("...done"); + cliSerial->printf("...done\n"); delay(50); @@ -195,7 +195,7 @@ int8_t Copter::test_optflow(uint8_t argc, const Menu::arg *argv) } } } else { - cliSerial->print("OptFlow: "); + cliSerial->printf("OptFlow: "); print_enabled(false); } return (0); @@ -210,14 +210,14 @@ int8_t Copter::test_relay(uint8_t argc, const Menu::arg *argv) delay(1000); while(1) { - cliSerial->println("Relay on"); + cliSerial->printf("Relay on\n"); relay.on(0); delay(3000); if(cliSerial->available() > 0) { return (0); } - cliSerial->println("Relay off"); + cliSerial->printf("Relay off\n"); relay.off(0); delay(3000); if(cliSerial->available() > 0) {