Arming: fix compile warnings re float constants

This commit is contained in:
Tom Pittenger 2015-04-24 12:26:52 +09:00 committed by Randy Mackay
parent e28c555889
commit 8f11507594

View File

@ -250,7 +250,7 @@ bool AP_Arming::compass_checks(bool report)
// check for unreasonable mag field length
float mag_field = _compass.get_field().length();
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65 || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35) {
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check mag field"));
}