diff --git a/libraries/AP_Compass/AP_Compass_MMC3416.cpp b/libraries/AP_Compass/AP_Compass_MMC3416.cpp index 4f60e67b77..6eedd5229e 100644 --- a/libraries/AP_Compass/AP_Compass_MMC3416.cpp +++ b/libraries/AP_Compass/AP_Compass_MMC3416.cpp @@ -220,7 +220,7 @@ void AP_Compass_MMC3416::timer() have_initial_offset = true; } else { // low pass changes to the offset - offset = offset * 0.95 + new_offset * 0.05; + offset = offset * 0.95f + new_offset * 0.05f; } #if 0 diff --git a/libraries/AP_Compass/Compass_PerMotor.cpp b/libraries/AP_Compass/Compass_PerMotor.cpp index cae61c707d..fa5d51a29d 100644 --- a/libraries/AP_Compass/Compass_PerMotor.cpp +++ b/libraries/AP_Compass/Compass_PerMotor.cpp @@ -117,7 +117,7 @@ float Compass_PerMotor::scaled_output(uint8_t motor) uint16_t pwm = hal.rcout->read_last_sent(motor_map[motor]); // get 0 to 1 motor demand - float output = (hal.rcout->scale_esc_to_unity(pwm)+1) * 0.5; + float output = (hal.rcout->scale_esc_to_unity(pwm)+1) * 0.5f; if (output <= 0) { return 0; diff --git a/libraries/AP_Compass/Compass_PerMotor.h b/libraries/AP_Compass/Compass_PerMotor.h index ab977b6d4c..348532b564 100644 --- a/libraries/AP_Compass/Compass_PerMotor.h +++ b/libraries/AP_Compass/Compass_PerMotor.h @@ -21,7 +21,7 @@ public: void set_voltage(float _voltage) { // simple low-pass on voltage - voltage = 0.9 * voltage + 0.1 * _voltage; + voltage = 0.9f * voltage + 0.1f * _voltage; } void calibration_start(void); diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index 591f9a9812..63f6f28f18 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -44,7 +44,7 @@ void CompassLearn::update(void) // setup the expected earth field at this location float declination_deg=0, inclination_deg=0, intensity_gauss=0; - AP_Declination::get_mag_field_ef(loc.lat*1.0e-7, loc.lng*1.0e-7, intensity_gauss, declination_deg, inclination_deg); + AP_Declination::get_mag_field_ef(loc.lat*1.0e-7f, loc.lng*1.0e-7f, intensity_gauss, declination_deg, inclination_deg); // create earth field mag_ef = Vector3f(intensity_gauss*1000, 0.0, 0.0); @@ -213,7 +213,7 @@ void CompassLearn::process_sample(const struct sample &s) predicted_offsets[i] = offsets; } else { // lowpass the predicted offsets and the error - const float learn_rate = 0.92; + const float learn_rate = 0.92f; predicted_offsets[i] = predicted_offsets[i] * learn_rate + offsets * (1-learn_rate); errors[i] = errors[i] * learn_rate + delta * (1-learn_rate); }