From b02661b478bfbb4f5c66a924ce3234c7872c5afa Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Thu, 29 Oct 2015 12:49:10 -0200 Subject: [PATCH] APMrover2: fix wrong printf format for 32 bits Heading is a 32 bits value, so use %d. --- APMrover2/test.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/test.cpp b/APMrover2/test.cpp index 28be21fda7..e3d7c3df79 100644 --- a/APMrover2/test.cpp +++ b/APMrover2/test.cpp @@ -401,7 +401,7 @@ int8_t Rover::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);