mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_Param: load parameters from a comma-separated-list
This patch will break things for anyone who is using a comma in their filenames for their ardupilot defaults files.
This commit is contained in:
parent
fe189fefbc
commit
c93942695f
@ -1743,7 +1743,8 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value)
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error)
|
||||
// increments num_defaults for each default found in filename
|
||||
bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error)
|
||||
{
|
||||
FILE *f = fopen(filename, "r");
|
||||
if (f == nullptr) {
|
||||
@ -1819,11 +1820,23 @@ bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
||||
return false;
|
||||
}
|
||||
|
||||
uint16_t num_defaults = 0;
|
||||
if (!count_defaults_in_file(filename, num_defaults, panic_on_error)) {
|
||||
return false;
|
||||
char *mutable_filename = strdup(filename);
|
||||
if (mutable_filename == nullptr) {
|
||||
AP_HAL::panic("AP_Param: Failed to allocate mutable string");
|
||||
}
|
||||
|
||||
uint16_t num_defaults = 0;
|
||||
char *saveptr = nullptr;
|
||||
for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
|
||||
pname != nullptr;
|
||||
pname = strtok_r(nullptr, ",", &saveptr)) {
|
||||
if (!count_defaults_in_file(pname, num_defaults, panic_on_error)) {
|
||||
free(mutable_filename);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
free(mutable_filename);
|
||||
|
||||
if (param_overrides != nullptr) {
|
||||
free(param_overrides);
|
||||
}
|
||||
@ -1835,9 +1848,20 @@ bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
|
||||
return false;
|
||||
}
|
||||
|
||||
if (! read_param_defaults_file(filename)) {
|
||||
return false;
|
||||
saveptr = nullptr;
|
||||
mutable_filename = strdup(filename);
|
||||
if (mutable_filename == nullptr) {
|
||||
AP_HAL::panic("AP_Param: Failed to allocate mutable string");
|
||||
}
|
||||
for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
|
||||
pname != nullptr;
|
||||
pname = strtok_r(nullptr, ",", &saveptr)) {
|
||||
if (!read_param_defaults_file(pname)) {
|
||||
free(mutable_filename);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
free(mutable_filename);
|
||||
|
||||
num_param_overrides = num_defaults;
|
||||
|
||||
|
@ -510,7 +510,7 @@ 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 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
Block a user