mirror of https://github.com/ArduPilot/ardupilot
Copter: fixed build warnings
This commit is contained in:
parent
025e4edd17
commit
d14056fa1e
|
@ -1172,6 +1172,6 @@ void Copter::load_parameters(void)
|
|||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
||||
cliSerial->printf("load_all took %uus\n", micros() - before);
|
||||
cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -96,7 +96,7 @@ void Copter::init_ardupilot()
|
|||
|
||||
cliSerial->printf("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n",
|
||||
hal.util->available_memory());
|
||||
(unsigned)hal.util->available_memory());
|
||||
|
||||
//
|
||||
// Report firmware version code expect on console (check of actual EEPROM format version is done in load_parameters function)
|
||||
|
|
|
@ -119,7 +119,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
|
|||
const Vector3f &mag_ofs = compass.get_offsets();
|
||||
const Vector3f &mag = compass.get_field();
|
||||
cliSerial->printf("Heading: %d, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n",
|
||||
(wrap_360_cd(ToDeg(heading) * 100)) /100,
|
||||
(int)(wrap_360_cd(ToDeg(heading) * 100)) /100,
|
||||
(double)mag.x,
|
||||
(double)mag.y,
|
||||
(double)mag.z,
|
||||
|
|
Loading…
Reference in New Issue