From bde9a9421d67b8c8e5fac4b51f346f636af6e087 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 20 Oct 2015 14:37:00 -0700 Subject: [PATCH] AP_Param: panic on failure to load defaults file --- libraries/AP_Param/AP_Param.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index e5007aaf3b..8d5980ec76 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1376,6 +1376,8 @@ bool AP_Param::load_defaults_file(const char *filename) } if (!find_def_value_ptr(pname)) { fclose(f); + ::printf("invalid param %s in defaults file\n", pname); + AP_HAL::panic("AP_Param: Invalid param in defaults file"); return false; } num_defaults++; @@ -1389,6 +1391,7 @@ bool AP_Param::load_defaults_file(const char *filename) param_overrides = new param_override[num_defaults]; if (param_overrides == NULL) { + AP_HAL::panic("AP_Param: Failed to allocate overrides"); return false; } @@ -1397,6 +1400,7 @@ bool AP_Param::load_defaults_file(const char *filename) */ f = fopen(filename, "r"); if (f == NULL) { + AP_HAL::panic("AP_Param: Failed to re-open defaults file"); 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); if (!def_value_ptr) { fclose(f); + AP_HAL::panic("AP_Param: Invalid param in defaults file"); return false; } 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); if (!vp) { fclose(f); + AP_HAL::panic("AP_Param: Failed to set param default"); return false; } vp->set_float(value, var_type);