Plane: fixed float->double print warning

This commit is contained in:
Tom Pittenger 2016-05-17 15:57:26 -07:00
parent 1ac712fa65
commit 1a066cadd2
1 changed files with 1 additions and 1 deletions

View File

@ -443,7 +443,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
const Vector3f &mag_ofs = compass.get_offsets();
const Vector3f &mag = compass.get_field();
cliSerial->printf("Heading: %f, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n",
(wrap_360_cd(ToDeg(heading) * 100)) /100,
(double)((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);
} else {