AP_Compass: specify floating point constants

Probably indicates compiler floating-point-constants directive isn't
working
This commit is contained in:
Peter Barker 2019-04-04 11:36:58 +11:00 committed by Tom Pittenger
parent ae8862f266
commit 5455d27e84
4 changed files with 5 additions and 5 deletions

View File

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

View File

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

View File

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

View File

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