mirror of https://github.com/ArduPilot/ardupilot
AP_Param: simplify set_defaults_from_table error path
This commit is contained in:
parent
dfe2ade495
commit
bcee8b56ee
|
@ -2486,10 +2486,7 @@ void AP_Param::set_defaults_from_table(const struct defaults_table_struct *table
|
|||
{
|
||||
for (uint8_t i=0; i<count; i++) {
|
||||
if (!AP_Param::set_default_by_name(table[i].name, table[i].value)) {
|
||||
char *buf = nullptr;
|
||||
if (asprintf(&buf, "param deflt fail:%s", table[i].name) > 0) {
|
||||
AP_BoardConfig::config_error("%s", buf);
|
||||
}
|
||||
AP_BoardConfig::config_error("param deflt fail:%s", table[i].name);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue