mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_Param: panic on failure to load defaults file
This commit is contained in:
parent
0ffba07ec8
commit
bde9a9421d
@ -1376,6 +1376,8 @@ bool AP_Param::load_defaults_file(const char *filename)
|
|||||||
}
|
}
|
||||||
if (!find_def_value_ptr(pname)) {
|
if (!find_def_value_ptr(pname)) {
|
||||||
fclose(f);
|
fclose(f);
|
||||||
|
::printf("invalid param %s in defaults file\n", pname);
|
||||||
|
AP_HAL::panic("AP_Param: Invalid param in defaults file");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
num_defaults++;
|
num_defaults++;
|
||||||
@ -1389,6 +1391,7 @@ bool AP_Param::load_defaults_file(const char *filename)
|
|||||||
|
|
||||||
param_overrides = new param_override[num_defaults];
|
param_overrides = new param_override[num_defaults];
|
||||||
if (param_overrides == NULL) {
|
if (param_overrides == NULL) {
|
||||||
|
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1397,6 +1400,7 @@ bool AP_Param::load_defaults_file(const char *filename)
|
|||||||
*/
|
*/
|
||||||
f = fopen(filename, "r");
|
f = fopen(filename, "r");
|
||||||
if (f == NULL) {
|
if (f == NULL) {
|
||||||
|
AP_HAL::panic("AP_Param: Failed to re-open defaults file");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1410,6 +1414,7 @@ bool AP_Param::load_defaults_file(const char *filename)
|
|||||||
const float *def_value_ptr = find_def_value_ptr(pname);
|
const float *def_value_ptr = find_def_value_ptr(pname);
|
||||||
if (!def_value_ptr) {
|
if (!def_value_ptr) {
|
||||||
fclose(f);
|
fclose(f);
|
||||||
|
AP_HAL::panic("AP_Param: Invalid param in defaults file");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
param_overrides[idx].def_value_ptr = def_value_ptr;
|
param_overrides[idx].def_value_ptr = def_value_ptr;
|
||||||
@ -1419,6 +1424,7 @@ bool AP_Param::load_defaults_file(const char *filename)
|
|||||||
AP_Param *vp = AP_Param::find(pname, &var_type);
|
AP_Param *vp = AP_Param::find(pname, &var_type);
|
||||||
if (!vp) {
|
if (!vp) {
|
||||||
fclose(f);
|
fclose(f);
|
||||||
|
AP_HAL::panic("AP_Param: Failed to set param default");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
vp->set_float(value, var_type);
|
vp->set_float(value, var_type);
|
||||||
|
Loading…
Reference in New Issue
Block a user