From d40349d6aef50fab967e457948594aee52d9eb6a Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Mon, 26 Oct 2015 11:05:00 -0200 Subject: [PATCH] ArduPlane: fix wrong printf format for 32 bits Heading is a 32 bits value, so use %d. --- ArduPlane/test.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/test.cpp b/ArduPlane/test.cpp index 72ff85868f..7d8180c2b8 100644 --- a/ArduPlane/test.cpp +++ b/ArduPlane/test.cpp @@ -465,7 +465,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv) if (compass.healthy()) { const Vector3f &mag_ofs = compass.get_offsets(); const Vector3f &mag = compass.get_field(); - cliSerial->printf("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n", + cliSerial->printf("Heading: %d, 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, (double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z);