mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: 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
c3fe71a0d5
commit
68bef1ec64
@ -134,7 +134,7 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
|||||||
// a nested group
|
// a nested group
|
||||||
const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info);
|
const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info);
|
||||||
if (group_shift + _group_level_shift >= _group_bits) {
|
if (group_shift + _group_level_shift >= _group_bits) {
|
||||||
Debug("double group nesting in %S", group_info[i].name);
|
Debug("double group nesting in %s", group_info[i].name);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (ginfo == NULL ||
|
if (ginfo == NULL ||
|
||||||
@ -146,21 +146,21 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
|
|||||||
#endif // AP_NESTED_GROUPS_ENABLED
|
#endif // AP_NESTED_GROUPS_ENABLED
|
||||||
uint8_t idx = PGM_UINT8(&group_info[i].idx);
|
uint8_t idx = PGM_UINT8(&group_info[i].idx);
|
||||||
if (idx >= (1<<_group_level_shift)) {
|
if (idx >= (1<<_group_level_shift)) {
|
||||||
Debug("idx too large (%u) in %S", idx, group_info[i].name);
|
Debug("idx too large (%u) in %s", idx, group_info[i].name);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if ((int8_t)idx <= max_idx) {
|
if ((int8_t)idx <= max_idx) {
|
||||||
Debug("indexes must be in increasing order in %S", group_info[i].name);
|
Debug("indexes must be in increasing order in %s", group_info[i].name);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
max_idx = (int8_t)idx;
|
max_idx = (int8_t)idx;
|
||||||
uint8_t size = type_size((enum ap_var_type)type);
|
uint8_t size = type_size((enum ap_var_type)type);
|
||||||
if (size == 0) {
|
if (size == 0) {
|
||||||
Debug("invalid type in %S", group_info[i].name);
|
Debug("invalid type in %s", group_info[i].name);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (prefix_length + strlen(group_info[i].name) > 16) {
|
if (prefix_length + strlen(group_info[i].name) > 16) {
|
||||||
Debug("suffix is too long in %S", group_info[i].name);
|
Debug("suffix is too long in %s", group_info[i].name);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
(*total_size) += size + sizeof(struct Param_header);
|
(*total_size) += size + sizeof(struct Param_header);
|
||||||
|
Loading…
Reference in New Issue
Block a user