From 39fdc38c7195aff23a463334d458e3c3116b0b6c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 13 Sep 2022 19:26:41 +1000 Subject: [PATCH] AP_Param: make load_defaults_file() available on ChibiOS --- libraries/AP_Param/AP_Param.cpp | 4 ++-- libraries/AP_Param/AP_Param.h | 5 ++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 7952f5bf72..c29871e44c 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -2149,7 +2149,7 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &re } -#if HAL_OS_POSIX_IO == 1 +#if HAVE_FILESYSTEM_SUPPORT // increments num_defaults for each default found in filename bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults) @@ -2290,7 +2290,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) return true; } -#endif // HAL_OS_POSIX_IO +#endif // HAVE_FILESYSTEM_SUPPORT #if AP_PARAM_MAX_EMBEDDED_PARAM > 0 /* diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index bf2d79333e..2d56e90386 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -547,6 +547,8 @@ public: static bool load_int32(uint16_t key, uint32_t group_element, int32_t &value); #endif + static bool load_defaults_file(const char *filename, bool last_pass); + protected: // store default value in linked list @@ -696,14 +698,11 @@ private: static bool parse_param_line(char *line, char **vname, float &value, bool &read_only); -#if HAL_OS_POSIX_IO == 1 /* load a parameter defaults file. This happens as part of load_all() */ static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults); static bool read_param_defaults_file(const char *filename, bool last_pass); - static bool load_defaults_file(const char *filename, bool last_pass); -#endif /* load defaults from embedded parameters