diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 56d9cbf8ec..f1c6d949f6 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -39,6 +39,8 @@ #include #endif +#include "AP_Param_config.h" + extern const AP_HAL::HAL &hal; uint16_t AP_Param::sentinal_offset; @@ -1543,14 +1545,7 @@ bool AP_Param::load_all() */ void AP_Param::reload_defaults_file(bool last_pass) { -#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 - if (param_defaults_data.length != 0) { - load_embedded_param_defaults(last_pass); - return; - } -#endif - -#if AP_FILESYSTEM_POSIX_ENABLED +#if AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED /* if the HAL specifies a defaults parameter file then override defaults using that file @@ -1558,12 +1553,25 @@ void AP_Param::reload_defaults_file(bool last_pass) 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); +#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 + if (param_defaults_data.length != 0) { + load_embedded_param_defaults(last_pass); + } #endif + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) hal.util->set_cmdline_parameters(); #endif @@ -2136,8 +2144,7 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &re } -// FIXME: make this AP_FILESYSTEM_FILE_READING_ENABLED -#if AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED +#if AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED // increments num_defaults for each default found in filename bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults) @@ -2283,8 +2290,8 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) return true; } +#endif // AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED -#endif // AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED #if AP_PARAM_MAX_EMBEDDED_PARAM > 0 /* diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index db8fbde15f..85b211f7ad 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -29,6 +29,8 @@ #include #include +#include "AP_Param_config.h" + #include "float.h" #define AP_MAX_NAME_SIZE 16 @@ -46,11 +48,15 @@ maximum size of embedded parameter file */ #ifndef AP_PARAM_MAX_EMBEDDED_PARAM -#if BOARD_FLASH_SIZE <= 1024 -# define AP_PARAM_MAX_EMBEDDED_PARAM 1024 -#else -# define AP_PARAM_MAX_EMBEDDED_PARAM 8192 -#endif + #if FORCE_APJ_DEFAULT_PARAMETERS + #if BOARD_FLASH_SIZE <= 1024 + #define AP_PARAM_MAX_EMBEDDED_PARAM 1024 + #else + #define AP_PARAM_MAX_EMBEDDED_PARAM 8192 + #endif + #else + #define AP_PARAM_MAX_EMBEDDED_PARAM 0 + #endif #endif // allow for dynamically added tables when scripting enabled diff --git a/libraries/AP_Param/AP_Param_config.h b/libraries/AP_Param/AP_Param_config.h new file mode 100644 index 0000000000..181c9f04c3 --- /dev/null +++ b/libraries/AP_Param/AP_Param_config.h @@ -0,0 +1,13 @@ +#pragma once + +#include + +#include + +#ifndef AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED +#define AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED AP_FILESYSTEM_FILE_READING_ENABLED +#endif + +#ifndef FORCE_APJ_DEFAULT_PARAMETERS +#define FORCE_APJ_DEFAULT_PARAMETERS 0 +#endif