From a8dda9f2ed312e6ce7facdc521a9622e81ad92d5 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 24 Apr 2015 12:50:50 +0900 Subject: [PATCH] AP_Math: fix compile warnings re float constants --- libraries/AP_Math/AP_Math.cpp | 2 +- libraries/AP_Math/examples/eulers/eulers.pde | 28 +++++++++---------- .../AP_Math/examples/location/location.pde | 22 +++++++-------- 3 files changed, 26 insertions(+), 26 deletions(-) diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 19ef964a00..28f568a3bc 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -6,7 +6,7 @@ float safe_asin(float v) { if (isnan(v)) { - return 0.0; + return 0.0f; } if (v >= 1.0f) { return PI/2; diff --git a/libraries/AP_Math/examples/eulers/eulers.pde b/libraries/AP_Math/examples/eulers/eulers.pde index e4455111b3..8fc26c7e56 100644 --- a/libraries/AP_Math/examples/eulers/eulers.pde +++ b/libraries/AP_Math/examples/eulers/eulers.pde @@ -70,9 +70,9 @@ static void check_result(const char *msg, yaw2 += fmod(yaw2+PI, 2*PI); } - if (rad_diff(roll2,roll) > 0.01 || - rad_diff(pitch2, pitch) > 0.01 || - rad_diff(yaw2, yaw) > 0.01) { + if (rad_diff(roll2,roll) > 0.01f || + rad_diff(pitch2, pitch) > 0.01f || + rad_diff(yaw2, yaw) > 0.01f) { if (pitch >= PI/2 || pitch <= -PI/2 || ToDeg(rad_diff(pitch, PI/2)) < 1 || @@ -168,13 +168,13 @@ void test_quaternion_eulers(void) test_quaternion(1, -PI/4, 1); test_quaternion(1, 1, -PI/4); - test_quaternion(ToRad(89), 0, 0.1); - test_quaternion(0, ToRad(89), 0.1); - test_quaternion(0.1, 0, ToRad(89)); + test_quaternion(ToRad(89), 0, 0.1f); + test_quaternion(0, ToRad(89), 0.1f); + test_quaternion(0.1f, 0, ToRad(89)); - test_quaternion(ToRad(91), 0, 0.1); - test_quaternion(0, ToRad(91), 0.1); - test_quaternion(0.1, 0, ToRad(91)); + test_quaternion(ToRad(91), 0, 0.1f); + test_quaternion(0, ToRad(91), 0.1f); + test_quaternion(0.1f, 0, ToRad(91)); for (i=0; iprintln("matrix/quaternion tests\n"); - test_conversion(1, 1.1, 1.2); - test_conversion(1, -1.1, 1.2); - test_conversion(1, -1.1, -1.2); - test_conversion(-1, 1.1, -1.2); - test_conversion(-1, 1.1, 1.2); + test_conversion(1, 1.1f, 1.2f); + test_conversion(1, -1.1f, 1.2f); + test_conversion(1, -1.1f, -1.2f); + test_conversion(-1, 1.1f, -1.2f); + test_conversion(-1, 1.1f, 1.2f); for (i=0; iprintf("location_offset took %u usec\n", (unsigned)(hal.scheduler->micros() - t1)); dist2 = get_distance(loc, loc2); - bearing2 = get_bearing_cd(loc, loc2) * 0.01; + bearing2 = get_bearing_cd(loc, loc2) * 0.01f; float brg_error = bearing2-bearing; if (brg_error > 180) { brg_error -= 360; @@ -109,8 +109,8 @@ static void test_one_offset(const struct Location &loc, brg_error += 360; } - if (fabsf(dist - dist2) > 1.0 || - brg_error > 1.0) { + if (fabsf(dist - dist2) > 1.0f || + brg_error > 1.0f) { hal.console->printf("Failed offset test brg_error=%f dist_error=%f\n", brg_error, dist-dist2); } @@ -119,8 +119,8 @@ static void test_one_offset(const struct Location &loc, static const struct { float ofs_north, ofs_east, distance, bearing; } test_offsets[] = { - { 1000, 1000, sqrt(2.0)*1000, 45 }, - { 1000, -1000, sqrt(2.0)*1000, -45 }, + { 1000, 1000, sqrt(2.0f)*1000, 45 }, + { 1000, -1000, sqrt(2.0f)*1000, -45 }, { 1000, 0, 1000, 0 }, { 0, 1000, 1000, 90 }, };