mirror of https://github.com/ArduPilot/ardupilot
DataFlash: 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
bdd1d5e9d4
commit
d2a259cef0
|
@ -320,7 +320,7 @@ void DataFlash_Backend::_print_log_entry(uint8_t msg_type,
|
||||||
if (!ReadBlock(pkt, msg_len)) {
|
if (!ReadBlock(pkt, msg_len)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
port->printf("%S, ", _structures[i].name);
|
port->printf("%s, ", _structures[i].name);
|
||||||
for (uint8_t ofs=0, fmt_ofs=0; ofs<msg_len; fmt_ofs++) {
|
for (uint8_t ofs=0, fmt_ofs=0; ofs<msg_len; fmt_ofs++) {
|
||||||
char fmt = PGM_UINT8(&_structures[i].format[fmt_ofs]);
|
char fmt = PGM_UINT8(&_structures[i].format[fmt_ofs]);
|
||||||
switch (fmt) {
|
switch (fmt) {
|
||||||
|
@ -478,7 +478,7 @@ void DataFlash_Block::_print_log_formats(AP_HAL::BetterStream *port)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<_num_types; i++) {
|
for (uint8_t i=0; i<_num_types; i++) {
|
||||||
const struct LogStructure *s = &_structures[i];
|
const struct LogStructure *s = &_structures[i];
|
||||||
port->printf("FMT, %u, %u, %S, %S, %S\n",
|
port->printf("FMT, %u, %u, %s, %s, %s\n",
|
||||||
(unsigned)PGM_UINT8(&s->msg_type),
|
(unsigned)PGM_UINT8(&s->msg_type),
|
||||||
(unsigned)PGM_UINT8(&s->msg_len),
|
(unsigned)PGM_UINT8(&s->msg_len),
|
||||||
s->name, s->format, s->labels);
|
s->name, s->format, s->labels);
|
||||||
|
|
Loading…
Reference in New Issue