mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: 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
b02661b478
commit
62ba8266ef
|
@ -617,7 +617,7 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
interact->printf(
|
interact->printf(
|
||||||
"Place vehicle %S and press any key.\n", msg);
|
"Place vehicle %s and press any key.\n", msg);
|
||||||
|
|
||||||
// wait for user input
|
// wait for user input
|
||||||
if (!interact->blocking_read()) {
|
if (!interact->blocking_read()) {
|
||||||
|
|
Loading…
Reference in New Issue