diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index f5cd4afb7a..72465be62d 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -257,7 +257,7 @@ bool AP_Arming::compass_checks(bool report) } // check for unreasonable compass offsets - Vector3f offsets = _compass.get_offsets(); + Vector3f offsets = _compass.get_offsets_milligauss(); if (offsets.length() > 600) { if (report) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Compass offsets too high")); @@ -272,7 +272,7 @@ bool AP_Arming::compass_checks(bool report) #endif // check for unreasonable mag field length - float mag_field = _compass.get_field().length(); + float mag_field = _compass.get_field_milligauss().length(); if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) { if (report) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Check mag field"));