mirror of https://github.com/ArduPilot/ardupilot
AP_Param: use ROMFS API for defaults file parsing if no AP_FileSystem
This commit is contained in:
parent
8e2a634c72
commit
6ce4dfea57
|
@ -35,6 +35,8 @@
|
|||
#include <AP_InternalError/AP_InternalError.h>
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
#include <stdio.h>
|
||||
#include <AP_ROMFS/AP_ROMFS.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
#endif
|
||||
|
@ -1546,24 +1548,20 @@ bool AP_Param::load_all()
|
|||
void AP_Param::reload_defaults_file(bool last_pass)
|
||||
{
|
||||
#if AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED
|
||||
|
||||
/*
|
||||
if the HAL specifies a defaults parameter file then override
|
||||
defaults using that file
|
||||
*/
|
||||
const char *default_file = hal.util->get_custom_defaults_file();
|
||||
if (default_file) {
|
||||
if (load_defaults_file(default_file, last_pass)) {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
printf("Loaded defaults from %s\n", default_file);
|
||||
#if AP_FILESYSTEM_FILE_READING_ENABLED
|
||||
load_defaults_file_from_filesystem(default_file, last_pass);
|
||||
#elif defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H)
|
||||
load_defaults_file_from_romfs(default_file, last_pass);
|
||||
#endif
|
||||
} else {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
AP_HAL::panic("Failed to load defaults from %s\n", default_file);
|
||||
#else
|
||||
printf("Failed to load defaults from %s\n", default_file);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif // AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED
|
||||
|
||||
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
||||
|
@ -1577,6 +1575,47 @@ void AP_Param::reload_defaults_file(bool last_pass)
|
|||
#endif
|
||||
}
|
||||
|
||||
#if AP_FILESYSTEM_FILE_READING_ENABLED
|
||||
void AP_Param::load_defaults_file_from_filesystem(const char *default_file, bool last_pass)
|
||||
{
|
||||
if (load_defaults_file(default_file, last_pass)) {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
printf("Loaded defaults from %s\n", default_file);
|
||||
#endif
|
||||
} else {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
AP_HAL::panic("Failed to load defaults from %s\n", default_file);
|
||||
#else
|
||||
printf("Failed to load defaults from %s\n", default_file);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif // AP_FILESYSTEM_FILE_READING_ENABLED
|
||||
|
||||
#if defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H)
|
||||
void AP_Param::load_defaults_file_from_romfs(const char *default_file, bool last_pass)
|
||||
{
|
||||
const char *prefix = "@ROMFS/";
|
||||
if (strncmp(default_file, prefix, strlen(prefix)) != 0) {
|
||||
// does not start with ROMFS, do not attempt to retrieve from it
|
||||
return;
|
||||
}
|
||||
|
||||
// filename without the prefix:
|
||||
const char *trimmed_filename = &default_file[strlen(prefix)];
|
||||
|
||||
uint32_t string_length;
|
||||
const uint8_t *text = AP_ROMFS::find_decompress(trimmed_filename, string_length);
|
||||
if (text == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
load_param_defaults((const char*)text, string_length, last_pass);
|
||||
|
||||
AP_ROMFS::free(text);
|
||||
|
||||
}
|
||||
#endif // HAL_HAVE_AP_ROMFS_EMBEDDED_H
|
||||
|
||||
/*
|
||||
Load all variables from EEPROM for a particular object. This is
|
||||
|
@ -2293,14 +2332,12 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass)
|
|||
#endif // AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED
|
||||
|
||||
|
||||
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
||||
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 || (!AP_FILESYSTEM_FILE_READING_ENABLED && defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H))
|
||||
/*
|
||||
count the number of embedded parameter defaults
|
||||
count the number of parameter defaults present in supplied string
|
||||
*/
|
||||
bool AP_Param::count_embedded_param_defaults(uint16_t &count)
|
||||
bool AP_Param::count_param_defaults(const volatile char *ptr, int32_t length, uint16_t &count)
|
||||
{
|
||||
const volatile char *ptr = param_defaults_data.data;
|
||||
int32_t length = param_defaults_data.length;
|
||||
count = 0;
|
||||
|
||||
while (length>0) {
|
||||
|
@ -2341,12 +2378,22 @@ bool AP_Param::count_embedded_param_defaults(uint16_t &count)
|
|||
return true;
|
||||
}
|
||||
|
||||
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
||||
/*
|
||||
* load a default set of parameters from a embedded parameter region
|
||||
* @last_pass: if this is the last pass on defaults - unknown parameters are
|
||||
* ignored but if this is set a warning will be emitted
|
||||
*/
|
||||
void AP_Param::load_embedded_param_defaults(bool last_pass)
|
||||
{
|
||||
load_param_defaults(param_defaults_data.data, param_defaults_data.length, last_pass);
|
||||
}
|
||||
#endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
||||
|
||||
/*
|
||||
* load parameter defaults from supplied string
|
||||
*/
|
||||
void AP_Param::load_param_defaults(const volatile char *ptr, int32_t length, bool last_pass)
|
||||
{
|
||||
delete[] param_overrides;
|
||||
param_overrides = nullptr;
|
||||
|
@ -2355,7 +2402,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
|
|||
num_read_only = 0;
|
||||
|
||||
uint16_t num_defaults = 0;
|
||||
if (!count_embedded_param_defaults(num_defaults)) {
|
||||
if (!count_param_defaults(ptr, length, num_defaults)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -2367,8 +2414,6 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
|
|||
|
||||
param_overrides_len = num_defaults;
|
||||
|
||||
const volatile char *ptr = param_defaults_data.data;
|
||||
int32_t length = param_defaults_data.length;
|
||||
uint16_t idx = 0;
|
||||
|
||||
while (idx < num_defaults && length > 0) {
|
||||
|
|
|
@ -732,8 +732,17 @@ private:
|
|||
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_param_defaults(const volatile char *ptr, int32_t length, uint16_t &count);
|
||||
static bool read_param_defaults_file(const char *filename, bool last_pass, uint16_t &idx);
|
||||
|
||||
// load a defaults.parm using AP_FileSystem:
|
||||
static void load_defaults_file_from_filesystem(const char *filename, bool lastpass);
|
||||
// load an @ROMFS defaults.parm using ROMFS API:
|
||||
static void load_defaults_file_from_romfs(const char *filename, bool lastpass);
|
||||
|
||||
// load defaults from supplied string:
|
||||
static void load_param_defaults(const volatile char *ptr, int32_t length, bool last_pass);
|
||||
|
||||
/*
|
||||
load defaults from embedded parameters
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue