ArduCopter: fix wrong printf format for 32 bits

Heading is a 32 bits value, so use %u.
This commit is contained in:
Lucas De Marchi 2015-10-26 11:05:00 -02:00 committed by Randy Mackay
parent a6fd94c6fe
commit f4e71affa1
1 changed files with 1 additions and 1 deletions

View File

@ -118,7 +118,7 @@ int8_t Copter::test_compass(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,