Browse Source

Plane: Unify from print or println to printf.

mission-4.1.18
murata 8 years ago committed by Andrew Tridgell
parent
commit
2492b9db7e
  1. 14
      ArduPlane/Log.cpp
  2. 6
      ArduPlane/Parameters.cpp
  3. 16
      ArduPlane/px4_mixer.cpp
  4. 2
      ArduPlane/setup.cpp
  5. 48
      ArduPlane/system.cpp
  6. 26
      ArduPlane/test.cpp

14
ArduPlane/Log.cpp

@ -23,10 +23,10 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&plane, &Plane::print_log @@ -23,10 +23,10 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&plane, &Plane::print_log
bool Plane::print_log_menu(void)
{
cliSerial->println("logs enabled: ");
cliSerial->printf("logs enabled: \n");
if (0 == g.log_bitmask) {
cliSerial->println("none");
cliSerial->printf("none\n");
}else{
// Macro to make the following code a bit easier on the eye.
// Pass it the capitalised name of the log option, as defined
@ -51,7 +51,7 @@ bool Plane::print_log_menu(void) @@ -51,7 +51,7 @@ bool Plane::print_log_menu(void)
#undef PLOG
}
cliSerial->println();
cliSerial->printf("\n");
DataFlash.ListAvailableLogs(cliSerial);
return(true);
@ -70,11 +70,11 @@ int8_t Plane::dump_log(uint8_t argc, const Menu::arg *argv) @@ -70,11 +70,11 @@ int8_t Plane::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);
}
@ -96,7 +96,7 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv) @@ -96,7 +96,7 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
uint32_t bits;
if (argc != 2) {
cliSerial->println("missing log type");
cliSerial->printf("missing log type\n");
return(-1);
}
@ -503,7 +503,7 @@ void Plane::Log_Read(uint16_t list_entry, int16_t start_page, int16_t end_page) @@ -503,7 +503,7 @@ void Plane::Log_Read(uint16_t list_entry, int16_t start_page, int16_t end_page)
"\nFree RAM: %u\n",
(unsigned)hal.util->available_memory());
cliSerial->println(HAL_BOARD_NAME);
cliSerial->printf("%s\n", HAL_BOARD_NAME);
DataFlash.LogReadProcess(list_entry, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Plane::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),

6
ArduPlane/Parameters.cpp

@ -1303,19 +1303,19 @@ const AP_Param::ConversionInfo conversion_table[] = { @@ -1303,19 +1303,19 @@ const AP_Param::ConversionInfo conversion_table[] = {
void Plane::load_parameters(void)
{
if (!AP_Param::check_var_info()) {
cliSerial->println("Bad parameter table");
cliSerial->printf("Bad parameter table\n");
AP_HAL::panic("Bad parameter table");
}
if (!g.format_version.load() ||
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();

16
ArduPlane/px4_mixer.cpp

@ -246,7 +246,7 @@ bool Plane::setup_failsafe_mixing(void) @@ -246,7 +246,7 @@ bool Plane::setup_failsafe_mixing(void)
fileSize = create_mixer(buf, buf_size, mixer_filename);
if (!fileSize) {
hal.console->println("Unable to create mixer");
hal.console->printf("Unable to create mixer\n");
goto failed;
}
@ -280,13 +280,13 @@ bool Plane::setup_failsafe_mixing(void) @@ -280,13 +280,13 @@ bool Plane::setup_failsafe_mixing(void)
/* reset any existing mixer in px4io. This shouldn't be needed,
* but is good practice */
if (ioctl(px4io_fd, MIXERIOCRESET, 0) != 0) {
hal.console->println("Unable to reset mixer");
hal.console->printf("Unable to reset mixer\n");
goto failed;
}
/* pass the buffer to the device */
if (ioctl(px4io_fd, MIXERIOCLOADBUF, (unsigned long)buf) != 0) {
hal.console->println("Unable to send mixer to IO");
hal.console->printf("Unable to send mixer to IO\n");
goto failed;
}
@ -348,7 +348,7 @@ bool Plane::setup_failsafe_mixing(void) @@ -348,7 +348,7 @@ bool Plane::setup_failsafe_mixing(void)
}
if (ioctl(px4io_fd, PWM_SERVO_SET_RC_CONFIG, (unsigned long)&config) != 0) {
hal.console->println("SET_RC_CONFIG failed");
hal.console->printf("SET_RC_CONFIG failed\n");
goto failed;
}
}
@ -362,7 +362,7 @@ bool Plane::setup_failsafe_mixing(void) @@ -362,7 +362,7 @@ bool Plane::setup_failsafe_mixing(void)
}
}
if (ioctl(px4io_fd, PWM_SERVO_SET_MIN_PWM, (long unsigned int)&pwm_values) != 0) {
hal.console->println("SET_MIN_PWM failed");
hal.console->printf("SET_MIN_PWM failed\n");
goto failed;
}
@ -376,16 +376,16 @@ bool Plane::setup_failsafe_mixing(void) @@ -376,16 +376,16 @@ bool Plane::setup_failsafe_mixing(void)
}
}
if (ioctl(px4io_fd, PWM_SERVO_SET_MAX_PWM, (long unsigned int)&pwm_values) != 0) {
hal.console->println("SET_MAX_PWM failed");
hal.console->printf("SET_MAX_PWM failed\n");
goto failed;
}
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0) != 0) {
hal.console->println("SET_OVERRIDE_OK failed");
hal.console->printf("SET_OVERRIDE_OK failed\n");
goto failed;
}
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 1) != 0) {
hal.console->println("SET_OVERRIDE_IMMEDIATE failed");
hal.console->printf("SET_OVERRIDE_IMMEDIATE failed\n");
goto failed;
}

2
ArduPlane/setup.cpp

@ -73,7 +73,7 @@ void Plane::zero_eeprom(void) @@ -73,7 +73,7 @@ void Plane::zero_eeprom(void)
{
cliSerial->printf("\nErasing EEPROM\n");
StorageManager::erase();
cliSerial->println("done");
cliSerial->printf("done\n");
}
#endif // CLI_ENABLED

48
ArduPlane/system.cpp

@ -188,7 +188,7 @@ void Plane::init_ardupilot() @@ -188,7 +188,7 @@ void Plane::init_ardupilot()
}
#endif
if (!compass_ok) {
cliSerial->println("Compass initialisation failed!");
cliSerial->printf("Compass initialisation failed!\n");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
@ -231,12 +231,12 @@ void Plane::init_ardupilot() @@ -231,12 +231,12 @@ void Plane::init_ardupilot()
#if CLI_ENABLED == ENABLED
if (g.cli_enabled == 1) {
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
@ -679,61 +679,61 @@ void Plane::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) @@ -679,61 +679,61 @@ void Plane::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
{
switch (mode) {
case MANUAL:
port->print("Manual");
port->printf("Manual");
break;
case CIRCLE:
port->print("Circle");
port->printf("Circle");
break;
case STABILIZE:
port->print("Stabilize");
port->printf("Stabilize");
break;
case TRAINING:
port->print("Training");
port->printf("Training");
break;
case ACRO:
port->print("ACRO");
port->printf("ACRO");
break;
case FLY_BY_WIRE_A:
port->print("FBW_A");
port->printf("FBW_A");
break;
case AUTOTUNE:
port->print("AUTOTUNE");
port->printf("AUTOTUNE");
break;
case FLY_BY_WIRE_B:
port->print("FBW_B");
port->printf("FBW_B");
break;
case CRUISE:
port->print("CRUISE");
port->printf("CRUISE");
break;
case AUTO:
port->print("AUTO");
port->printf("AUTO");
break;
case RTL:
port->print("RTL");
port->printf("RTL");
break;
case LOITER:
port->print("Loiter");
port->printf("Loiter");
break;
case AVOID_ADSB:
port->print("AVOID_ADSB");
port->printf("AVOID_ADSB");
break;
case GUIDED:
port->print("Guided");
port->printf("Guided");
break;
case QSTABILIZE:
port->print("QStabilize");
port->printf("QStabilize");
break;
case QHOVER:
port->print("QHover");
port->printf("QHover");
break;
case QLOITER:
port->print("QLoiter");
port->printf("QLoiter");
break;
case QLAND:
port->print("QLand");
port->printf("QLand");
break;
case QRTL:
port->print("QRTL");
port->printf("QRTL");
break;
default:
port->printf("Mode(%u)", (unsigned)mode);
@ -817,7 +817,7 @@ void Plane::notify_flight_mode(enum FlightMode mode) @@ -817,7 +817,7 @@ void Plane::notify_flight_mode(enum FlightMode mode)
#if CLI_ENABLED == ENABLED
void Plane::print_comma(void)
{
cliSerial->print(",");
cliSerial->printf(",");
}
#endif

26
ArduPlane/test.cpp

@ -79,7 +79,7 @@ int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv) @@ -79,7 +79,7 @@ int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv)
(long)loc.alt/100,
(int)gps.num_sats());
} else {
cliSerial->print(".");
cliSerial->printf(".");
}
if(cliSerial->available() > 0) {
return (0);
@ -89,7 +89,7 @@ int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv) @@ -89,7 +89,7 @@ int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv)
int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
{
//cliSerial->print("Calibrating.");
//cliSerial->printf("Calibrating.");
ahrs.init();
ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true);
@ -140,13 +140,13 @@ int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv) @@ -140,13 +140,13 @@ int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
{
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;
}
ahrs.init();
@ -191,7 +191,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv) @@ -191,7 +191,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
(double)mag.x, (double)mag.y, (double)mag.z,
(double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z);
} else {
cliSerial->println("compass not healthy");
cliSerial->printf("compass not healthy\n");
}
counter=0;
}
@ -203,7 +203,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv) @@ -203,7 +203,7 @@ int8_t Plane::test_mag(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);
}
@ -214,13 +214,13 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv) @@ -214,13 +214,13 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv)
{
if (!airspeed.enabled()) {
cliSerial->print("airspeed: ");
cliSerial->printf("airspeed: ");
print_enabled(false);
return (0);
}else{
print_hit_enter();
zero_airspeed(false);
cliSerial->print("airspeed: ");
cliSerial->printf("airspeed: ");
print_enabled(true);
while(1) {
@ -238,7 +238,7 @@ int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv) @@ -238,7 +238,7 @@ int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv)
int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
{
cliSerial->println("Uncalibrated relative airpressure");
cliSerial->printf("Uncalibrated relative airpressure\n");
print_hit_enter();
init_barometer(true);
@ -248,7 +248,7 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv) @@ -248,7 +248,7 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
barometer.update();
if (!barometer.healthy()) {
cliSerial->println("not healthy");
cliSerial->printf("not healthy\n");
} else {
cliSerial->printf("Alt: %0.2fm, Raw: %f Temperature: %.1f\n",
(double)barometer.get_altitude(),
@ -265,11 +265,11 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv) @@ -265,11 +265,11 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
void Plane::print_enabled(bool b)
{
if (b) {
cliSerial->print("en");
cliSerial->printf("en");
} else {
cliSerial->print("dis");
cliSerial->printf("dis");
}
cliSerial->println("abled");
cliSerial->printf("abled\n");
}
#endif // CLI_ENABLED

Loading…
Cancel
Save