ArduPlane: 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
d2a259cef0
commit
cfe6e209db
@ -33,7 +33,7 @@ bool Plane::print_log_menu(void)
|
|||||||
// Pass it the capitalised name of the log option, as defined
|
// Pass it the capitalised name of the log option, as defined
|
||||||
// in defines.h but without the LOG_ prefix. It will check for
|
// in defines.h but without the LOG_ prefix. It will check for
|
||||||
// the bit being set and print the name of the log option to suit.
|
// the bit being set and print the name of the log option to suit.
|
||||||
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf(" %S", # _s)
|
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf(" %s", # _s)
|
||||||
PLOG(ATTITUDE_FAST);
|
PLOG(ATTITUDE_FAST);
|
||||||
PLOG(ATTITUDE_MED);
|
PLOG(ATTITUDE_MED);
|
||||||
PLOG(GPS);
|
PLOG(GPS);
|
||||||
|
Loading…
Reference in New Issue
Block a user