ArduPlane: use compass get_{field,offsets}() functions

Both functions are equivalent, so we're going to simply use
get_{field,offsets}() instead of get_{field,offsets}_milligauss().
This commit is contained in:
Gustavo Jose de Sousa 2015-09-28 16:57:09 -03:00 committed by Randy Mackay
parent fb5320bb25
commit 2cc07d2899

View File

@ -463,8 +463,8 @@ int8_t Plane::test_mag(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, (double)mag.y, (double)mag.z,