mirror of https://github.com/ArduPilot/ardupilot
AP_Param: Factor load_defaults_file (NFC)
This commit is contained in:
parent
0a381dfa1b
commit
fe189fefbc
|
@ -1743,14 +1743,8 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value)
|
|||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
load a default set of parameters from a file
|
||||
*/
|
||||
bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
||||
uint16_t AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error)
|
||||
{
|
||||
if (filename == nullptr) {
|
||||
return false;
|
||||
}
|
||||
FILE *f = fopen(filename, "r");
|
||||
if (f == nullptr) {
|
||||
return false;
|
||||
|
@ -1760,7 +1754,6 @@ bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
|||
/*
|
||||
work out how many parameter default structures to allocate
|
||||
*/
|
||||
uint16_t num_defaults = 0;
|
||||
while (fgets(line, sizeof(line)-1, f)) {
|
||||
char *pname;
|
||||
float value;
|
||||
|
@ -1782,27 +1775,19 @@ bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
|||
}
|
||||
fclose(f);
|
||||
|
||||
if (param_overrides != nullptr) {
|
||||
free(param_overrides);
|
||||
}
|
||||
num_param_overrides = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
param_overrides = new param_override[num_defaults];
|
||||
if (param_overrides == nullptr) {
|
||||
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
re-open to avoid possible seek issues with NuttX
|
||||
*/
|
||||
f = fopen(filename, "r");
|
||||
bool AP_Param::read_param_defaults_file(const char *filename)
|
||||
{
|
||||
FILE *f = fopen(filename, "r");
|
||||
if (f == nullptr) {
|
||||
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)) {
|
||||
char *pname;
|
||||
float value;
|
||||
|
@ -1822,6 +1807,37 @@ bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
|||
}
|
||||
}
|
||||
fclose(f);
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
load a default set of parameters from a file
|
||||
*/
|
||||
bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
||||
{
|
||||
if (filename == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint16_t num_defaults = 0;
|
||||
if (!count_defaults_in_file(filename, num_defaults, panic_on_error)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (param_overrides != nullptr) {
|
||||
free(param_overrides);
|
||||
}
|
||||
num_param_overrides = 0;
|
||||
|
||||
param_overrides = new param_override[num_defaults];
|
||||
if (param_overrides == nullptr) {
|
||||
AP_HAL::panic("AP_Param: Failed to allocate overrides");
|
||||
return false;
|
||||
}
|
||||
|
||||
if (! read_param_defaults_file(filename)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
num_param_overrides = num_defaults;
|
||||
|
||||
|
|
|
@ -510,6 +510,8 @@ private:
|
|||
load a parameter defaults file. This happens as part of load_all()
|
||||
*/
|
||||
static bool parse_param_line(char *line, char **vname, float &value);
|
||||
static uint16_t count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error);
|
||||
static bool read_param_defaults_file(const char *filename);
|
||||
static bool load_defaults_file(const char *filename, bool panic_on_error);
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue