From e6929892e36405b62cc6a002b85b4a09ba27356d Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 25 Jan 2022 13:47:58 -0300 Subject: [PATCH] AP_Param: Use AP:FS() to read files --- libraries/AP_Param/AP_Param.cpp | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 1bbba058aa..a8a19cd74a 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -33,6 +33,7 @@ #include #include #include +#include #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -2109,8 +2110,8 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &re // increments num_defaults for each default found in filename bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults) { - FILE *f = fopen(filename, "r"); - if (f == nullptr) { + int f = AP::FS().open(filename, O_RDONLY);; + if (f == -1) { return false; } char line[100]; @@ -2118,7 +2119,7 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul /* work out how many parameter default structures to allocate */ - while (fgets(line, sizeof(line)-1, f)) { + while (AP::FS().fgets(line, sizeof(line)-1, f)) { char *pname; float value; bool read_only; @@ -2132,22 +2133,22 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul num_defaults++; } - fclose(f); + AP::FS().close(f); return true; } bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass) { - FILE *f = fopen(filename, "r"); - if (f == nullptr) { + int f = AP::FS().open(filename, O_RDONLY);; + if (f == -1) { AP_HAL::panic("AP_Param: Failed to re-open defaults file"); return false; } uint16_t idx = 0; char line[100]; - while (fgets(line, sizeof(line)-1, f)) { + while (AP::FS().fgets(line, sizeof(line)-1, f)) { char *pname; float value; bool read_only; @@ -2179,7 +2180,7 @@ bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass) vp->set_float(value, var_type); } } - fclose(f); + AP::FS().close(f); return true; }