Browse Source

AP_Param: simplify set_defaults_from_table error path

gps-1.3.1
Peter Barker 3 years ago committed by Peter Barker
parent
commit
bcee8b56ee
  1. 5
      libraries/AP_Param/AP_Param.cpp

5
libraries/AP_Param/AP_Param.cpp

@ -2486,10 +2486,7 @@ void AP_Param::set_defaults_from_table(const struct defaults_table_struct *table @@ -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…
Cancel
Save