From ec4cce15a1e631a448dd73cf8bd96517dba6997e Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 21 Jan 2017 13:42:36 +0900 Subject: [PATCH] AP_Math: Unify from print or println to printf. --- libraries/AP_Math/examples/eulers/eulers.cpp | 16 ++++++++-------- libraries/AP_Math/examples/location/location.cpp | 4 ++-- .../AP_Math/examples/matrix_alg/matrix_alg.cpp | 4 ++-- libraries/AP_Math/examples/polygon/polygon.cpp | 12 ++++++------ .../AP_Math/examples/rotations/rotations.cpp | 12 ++++++------ 5 files changed, 24 insertions(+), 24 deletions(-) diff --git a/libraries/AP_Math/examples/eulers/eulers.cpp b/libraries/AP_Math/examples/eulers/eulers.cpp index 6f8a4f153b..5d9a7a5fdc 100644 --- a/libraries/AP_Math/examples/eulers/eulers.cpp +++ b/libraries/AP_Math/examples/eulers/eulers.cpp @@ -84,14 +84,14 @@ void test_matrix_eulers(void) uint8_t i, j, k; uint8_t N = ARRAY_SIZE(angles); - hal.console->println("rotation matrix unit tests\n"); + hal.console->printf("rotation matrix unit tests\n\n"); for (i=0; iprintln("tests done\n"); + hal.console->printf("tests done\n\n"); } static void test_quaternion(float roll, float pitch, float yaw) @@ -123,7 +123,7 @@ void test_quaternion_eulers(void) uint8_t i, j, k; uint8_t N = ARRAY_SIZE(angles); - hal.console->println("quaternion unit tests\n"); + hal.console->printf("quaternion unit tests\n\n"); test_quaternion(M_PI/4, 0, 0); test_quaternion(0, M_PI/4, 0); @@ -148,7 +148,7 @@ void test_quaternion_eulers(void) for (k=0; kprintln("tests done\n"); + hal.console->printf("tests done\n\n"); } @@ -183,7 +183,7 @@ void test_conversions(void) uint8_t i, j, k; uint8_t N = ARRAY_SIZE(angles); - hal.console->println("matrix/quaternion tests\n"); + hal.console->printf("matrix/quaternion tests\n\n"); test_conversion(1, 1.1f, 1.2f); test_conversion(1, -1.1f, 1.2f); @@ -196,7 +196,7 @@ void test_conversions(void) for (k=0; kprintln("tests done\n"); + hal.console->printf("tests done\n\n"); } void test_frame_transforms(void) @@ -205,7 +205,7 @@ void test_frame_transforms(void) Quaternion q; Matrix3f m; - hal.console->println("frame transform tests\n"); + hal.console->printf("frame transform tests\n\n"); q.from_euler(ToRad(45), ToRad(45), ToRad(45)); q.normalize(); @@ -285,7 +285,7 @@ void test_matrix_rotate(void) */ void setup(void) { - hal.console->println("euler unit tests\n"); + hal.console->printf("euler unit tests\n\n"); test_conversion(0, M_PI, 0); diff --git a/libraries/AP_Math/examples/location/location.cpp b/libraries/AP_Math/examples/location/location.cpp index 1697f0496a..c1f94f2b71 100644 --- a/libraries/AP_Math/examples/location/location.cpp +++ b/libraries/AP_Math/examples/location/location.cpp @@ -44,7 +44,7 @@ static struct Location location_from_point(Vector2f pt) static void test_passed_waypoint(void) { - hal.console->println("waypoint tests starting"); + hal.console->printf("waypoint tests starting\n"); for (uint8_t i=0; iprintln("waypoint tests OK"); + hal.console->printf("waypoint tests OK\n"); } static void test_one_offset(const struct Location &loc, diff --git a/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp b/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp index 38d698e5bd..bcbdc0ff73 100644 --- a/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp +++ b/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp @@ -147,9 +147,9 @@ static void test_matrix_inverse(void) void setup(void) { - hal.console->println("Matrix Algebra test\n"); + hal.console->printf("Matrix Algebra test\n\n"); test_matrix_inverse(); - hal.console->println("Matrix Algebra tests done\n"); + hal.console->printf("Matrix Algebra tests done\n\n"); } void loop(void) {} diff --git a/libraries/AP_Math/examples/polygon/polygon.cpp b/libraries/AP_Math/examples/polygon/polygon.cpp index a33803a863..9311ee9af3 100644 --- a/libraries/AP_Math/examples/polygon/polygon.cpp +++ b/libraries/AP_Math/examples/polygon/polygon.cpp @@ -63,15 +63,15 @@ void setup(void) bool all_passed = true; uint32_t start_time; - hal.console->println("polygon unit tests\n"); + hal.console->printf("polygon unit tests\n\n"); if (!Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary))) { - hal.console->println("OBC boundary is not complete!"); + hal.console->printf("OBC boundary is not complete!\n"); all_passed = false; } if (Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary)-1)) { - hal.console->println("Polygon_complete test failed"); + hal.console->printf("Polygon_complete test failed\n"); all_passed = false; } @@ -88,9 +88,9 @@ void setup(void) all_passed = false; } } - hal.console->println(all_passed ? "TEST PASSED" : "TEST FAILED"); + hal.console->printf("%s\n", all_passed ? "TEST PASSED" : "TEST FAILED"); - hal.console->println("Speed test:"); + hal.console->printf("Speed test:\n"); start_time = AP_HAL::micros(); for (count=0; count<1000; count++) { for (i=0; iprintf("%u usec/call\n", (unsigned)((AP_HAL::micros() - start_time)/(count*ARRAY_SIZE(test_points)))); - hal.console->println(all_passed ? "ALL TESTS PASSED" : "TEST FAILED"); + hal.console->printf("%s\n", all_passed ? "ALL TESTS PASSED" : "TEST FAILED"); } void loop(void){} diff --git a/libraries/AP_Math/examples/rotations/rotations.cpp b/libraries/AP_Math/examples/rotations/rotations.cpp index df4bd33c27..76fbadc7f3 100644 --- a/libraries/AP_Math/examples/rotations/rotations.cpp +++ b/libraries/AP_Math/examples/rotations/rotations.cpp @@ -22,7 +22,7 @@ static void test_rotation_accuracy(void) int16_t i; float rot_angle; - hal.console->println("\nRotation method accuracy:"); + hal.console->printf("\nRotation method accuracy:\n"); // test roll for( i=0; i<90; i++ ) { @@ -150,7 +150,7 @@ static void test_euler(enum Rotation rotation, float roll, float pitch, float ya static void test_rotate_inverse(void) { - hal.console->println("\nrotate inverse test(Vector (1,1,1)):"); + hal.console->printf("\nrotate inverse test(Vector (1,1,1)):\n"); Vector3f vec(1.0f,1.0f,1.0f), cmp_vec(1.0f,1.0f,1.0f); for (enum Rotation r=ROTATION_NONE; rprintln("euler tests"); + hal.console->printf("euler tests\n"); test_euler(ROTATION_NONE, 0, 0, 0); test_euler(ROTATION_YAW_45, 0, 0, 45); test_euler(ROTATION_YAW_90, 0, 0, 90); @@ -231,7 +231,7 @@ static bool have_rotation(const Matrix3f &m) static void missing_rotations(void) { - hal.console->println("testing for missing rotations"); + hal.console->printf("testing for missing rotations\n"); uint16_t roll, pitch, yaw; for (yaw=0; yaw<360; yaw += 90) for (pitch=0; pitch<360; pitch += 90) @@ -249,12 +249,12 @@ static void missing_rotations(void) */ void setup(void) { - hal.console->println("rotation unit tests\n"); + hal.console->printf("rotation unit tests\n\n"); test_rotation_accuracy(); test_eulers(); missing_rotations(); test_rotate_inverse(); - hal.console->println("rotation unit tests done\n"); + hal.console->printf("rotation unit tests done\n\n"); } void loop(void) {}