mirror of https://github.com/ArduPilot/ardupilot
AP_Param: compile warnings: format not a string literal, argument types not checked
This commit is contained in:
parent
2301883d5c
commit
bfd1b2b11a
|
@ -1154,7 +1154,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info)
|
||||||
AP_Param *ap2;
|
AP_Param *ap2;
|
||||||
ap2 = find_P((const prog_char_t *)&info->new_name[0], &ptype);
|
ap2 = find_P((const prog_char_t *)&info->new_name[0], &ptype);
|
||||||
if (ap2 == NULL) {
|
if (ap2 == NULL) {
|
||||||
hal.console->printf_P(PSTR("Unknown conversion '%S'\n"), info->new_name);
|
hal.console->printf_P("Unknown conversion '%s'\n", info->new_name);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1184,7 +1184,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info)
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// can't do vector<->scalar conversion, or different vector types
|
// can't do vector<->scalar conversion, or different vector types
|
||||||
hal.console->printf_P(PSTR("Bad conversion type '%S'\n"), info->new_name);
|
hal.console->printf_P("Bad conversion type '%s'\n", info->new_name);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#pragma GCC diagnostic pop
|
#pragma GCC diagnostic pop
|
||||||
|
|
Loading…
Reference in New Issue