Compass: fix compile warnings re float constants

Also fix example sketch
This commit is contained in:
Tom Pittenger 2015-04-24 12:28:15 +09:00 committed by Randy Mackay
parent c1d4992dac
commit bf1d128d70
3 changed files with 5 additions and 5 deletions

View File

@ -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 {

View File

@ -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

View File

@ -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();