mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Menu: fix wrong printf format for printf
"%S" is used for wide string, but we are passing a char*. Use lowercase in this case to remove warnings like this: libraries/AP_InertialSensor/AP_InertialSensor.cpp: In member function 'bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract*, float&, float&)': libraries/AP_InertialSensor/AP_InertialSensor.cpp:620:61: warning: format '%S' expects argument of type 'wchar_t*', but argument 3 has type 'const char*' [-Wformat=] "Place vehicle %S and press any key.\n", msg); ^
This commit is contained in:
parent
62ba8266ef
commit
bdd1d5e9d4
@ -84,7 +84,7 @@ Menu::_check_for_input(void)
|
|||||||
void
|
void
|
||||||
Menu::_display_prompt(void)
|
Menu::_display_prompt(void)
|
||||||
{
|
{
|
||||||
_port->printf("%S] ", _prompt);
|
_port->printf("%s] ", _prompt);
|
||||||
}
|
}
|
||||||
|
|
||||||
// run the menu
|
// run the menu
|
||||||
@ -231,7 +231,7 @@ Menu::_help(void)
|
|||||||
_port->println("Commands:");
|
_port->println("Commands:");
|
||||||
for (i = 0; i < _entries; i++) {
|
for (i = 0; i < _entries; i++) {
|
||||||
hal.scheduler->delay(10);
|
hal.scheduler->delay(10);
|
||||||
_port->printf(" %S\n", _commands[i].command);
|
_port->printf(" %s\n", _commands[i].command);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user