mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_Param: make load_defaults_file() available on ChibiOS
This commit is contained in:
parent
8e102ecfcc
commit
39fdc38c71
@ -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
|
// increments num_defaults for each default found in filename
|
||||||
bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults)
|
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;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAL_OS_POSIX_IO
|
#endif // HAVE_FILESYSTEM_SUPPORT
|
||||||
|
|
||||||
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
||||||
/*
|
/*
|
||||||
|
@ -547,6 +547,8 @@ public:
|
|||||||
static bool load_int32(uint16_t key, uint32_t group_element, int32_t &value);
|
static bool load_int32(uint16_t key, uint32_t group_element, int32_t &value);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
static bool load_defaults_file(const char *filename, bool last_pass);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// store default value in linked list
|
// 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);
|
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()
|
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 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 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
|
load defaults from embedded parameters
|
||||||
|
Loading…
Reference in New Issue
Block a user