diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 88818a4acf..2b58fe5036 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -124,7 +124,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan) // store initial x,y,z compass values // initialise interference percentage for (uint8_t i=0; i COMPASS_OFFSETS_MAX) { if (display_failure) { gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass offsets too high")); @@ -367,7 +367,7 @@ bool Copter::pre_arm_checks(bool display_failure) } // check for unreasonable mag field length - float mag_field = compass.get_field_milligauss().length(); + float mag_field = compass.get_field().length(); if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) { if (display_failure) { gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check mag field")); diff --git a/ArduCopter/setup.cpp b/ArduCopter/setup.cpp index 62d3499eff..a003d13a03 100644 --- a/ArduCopter/setup.cpp +++ b/ArduCopter/setup.cpp @@ -450,7 +450,7 @@ void Copter::report_compass() // mag offsets Vector3f offsets; for (uint8_t i=0; iprintf_P(PSTR("Mag%d off: %4.4f, %4.4f, %4.4f\n"), (int)i, diff --git a/ArduCopter/test.cpp b/ArduCopter/test.cpp index 66f06d949c..f0fcae0b3b 100644 --- a/ArduCopter/test.cpp +++ b/ArduCopter/test.cpp @@ -116,8 +116,8 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv) counter++; if (counter>20) { if (compass.healthy()) { - const Vector3f &mag_ofs = compass.get_offsets_milligauss(); - const Vector3f &mag = compass.get_field_milligauss(); + const Vector3f &mag_ofs = compass.get_offsets(); + const Vector3f &mag = compass.get_field(); cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"), (wrap_360_cd(ToDeg(heading) * 100)) /100, (double)mag.x,