From 0733d760f6d738720881f159d350d1acaca4525f Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 21 Jan 2017 13:55:04 +0900 Subject: [PATCH] AP_HAL_VRBRAIN: Unify from print or println to printf. AP_InertialSensor: Unify from print or printin to printf. --- libraries/AP_HAL_VRBRAIN/AnalogIn.cpp | 2 +- .../examples/INS_generic/INS_generic.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp b/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp index 2b8a32a6d2..ab81defa8b 100644 --- a/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp +++ b/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp @@ -289,7 +289,7 @@ AP_HAL::AnalogSource* VRBRAINAnalogIn::channel(int16_t pin) return _channels[j]; } } - hal.console->println("Out of analog channels"); + hal.console->printf("Out of analog channels\n"); return nullptr; } diff --git a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp index 90de0a4d00..09791eed97 100644 --- a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp +++ b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp @@ -21,7 +21,7 @@ void setup(void) // setup any board specific drivers BoardConfig.init(); - hal.console->println("AP_InertialSensor startup..."); + hal.console->printf("AP_InertialSensor startup...\n"); ins.init(100); @@ -33,15 +33,15 @@ void setup(void) hal.console->printf("Number of detected accels : %u\n", ins.get_accel_count()); hal.console->printf("Number of detected gyros : %u\n\n", ins.get_gyro_count()); - hal.console->println("Complete. Reading:"); + hal.console->printf("Complete. Reading:\n"); } void loop(void) { int16_t user_input; - hal.console->println(); - hal.console->println( + hal.console->printf("\n"); + hal.console->printf("%s\n", "Menu:\n" " d) display offsets and scaling\n" " l) level (capture offsets from level)\n"