From bf1d128d7044beae86c022bce86becaca7e87dd9 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 24 Apr 2015 12:28:15 +0900 Subject: [PATCH] Compass: fix compile warnings re float constants Also fix example sketch --- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 2 +- libraries/AP_Compass/Compass_learn.cpp | 6 +++--- .../AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index 41aa20cae0..9bed11cf07 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -236,7 +236,7 @@ AP_Compass_HMC5843::init() */ expected_x = 766; expected_yz = 713; - gain_multiple = 660.0 / 1090; // adjustment for runtime vs calibration gain + gain_multiple = 660.0f / 1090; // adjustment for runtime vs calibration gain } else if (_base_config == (NormalOperation | DataOutputRate_75HZ<<2)) { _product_id = AP_COMPASS_TYPE_HMC5843; } else { diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index 33a60447cf..137a7b15af 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -34,9 +34,9 @@ Compass::learn_offsets(void) // this gain is set so we converge on the offsets in about 5 // minutes with a 10Hz compass - const float gain = 0.01; - const float max_change = 10.0; - const float min_diff = 50.0; + const float gain = 0.01f; + const float max_change = 10.0f; + const float min_diff = 50.0f; if (!_null_init_done) { // first time through diff --git a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde index 7932fcb322..e636a7a56f 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde +++ b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde @@ -53,7 +53,7 @@ void setup() { hal.console->printf("init done - %u compasses detected\n", compass.get_count()); compass.set_and_save_offsets(0,0,0,0); // set offsets to account for surrounding interference - compass.set_declination(ToRad(0.0)); // set local difference between magnetic north and true north + compass.set_declination(ToRad(0.0f)); // set local difference between magnetic north and true north hal.scheduler->delay(1000); timer = hal.scheduler->micros();