mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
APMrover2: 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:
parent
afccf615d5
commit
7c725bb59e
@ -399,8 +399,8 @@ int8_t Rover::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,
|
||||
|
Loading…
Reference in New Issue
Block a user