From 415d800957d77b28646053c3ba46c13365792167 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 7 Jan 2016 09:09:54 +1100 Subject: [PATCH] AP_Param: use get_custom_defaults_file() --- libraries/AP_Param/AP_Param.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index b8e733bfb4..005d95d6ef 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1081,9 +1081,7 @@ bool AP_Param::load_all(void) if the HAL specifies a defaults parameter file then override defaults using that file */ -#ifdef HAL_PARAM_DEFAULTS_PATH - load_defaults_file(HAL_PARAM_DEFAULTS_PATH); -#endif + load_defaults_file(hal.util->get_custom_defaults_file()); while (ofs < _storage.size()) { _storage.read_block(&phdr, ofs, sizeof(phdr)); @@ -1553,6 +1551,9 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value) */ bool AP_Param::load_defaults_file(const char *filename) { + if (filename == nullptr) { + return false; + } FILE *f = fopen(filename, "r"); if (f == NULL) { return false;