mirror of https://github.com/ArduPilot/ardupilot
AP_Param: use @ROMFS/defaults.parm rather than apj_tool for defaul parms
This commit is contained in:
parent
58408cd0b5
commit
27fa5f8d2c
|
@ -39,6 +39,8 @@
|
||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include "AP_Param_config.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
uint16_t AP_Param::sentinal_offset;
|
uint16_t AP_Param::sentinal_offset;
|
||||||
|
@ -1543,14 +1545,7 @@ bool AP_Param::load_all()
|
||||||
*/
|
*/
|
||||||
void AP_Param::reload_defaults_file(bool last_pass)
|
void AP_Param::reload_defaults_file(bool last_pass)
|
||||||
{
|
{
|
||||||
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
#if AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED
|
||||||
if (param_defaults_data.length != 0) {
|
|
||||||
load_embedded_param_defaults(last_pass);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if AP_FILESYSTEM_POSIX_ENABLED
|
|
||||||
/*
|
/*
|
||||||
if the HAL specifies a defaults parameter file then override
|
if the HAL specifies a defaults parameter file then override
|
||||||
defaults using that file
|
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();
|
const char *default_file = hal.util->get_custom_defaults_file();
|
||||||
if (default_file) {
|
if (default_file) {
|
||||||
if (load_defaults_file(default_file, 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);
|
printf("Loaded defaults from %s\n", default_file);
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
AP_HAL::panic("Failed to load defaults from %s\n", default_file);
|
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
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
|
||||||
hal.util->set_cmdline_parameters();
|
hal.util->set_cmdline_parameters();
|
||||||
#endif
|
#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_PARAM_DEFAULTS_FILE_PARSING_ENABLED
|
||||||
#if AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED
|
|
||||||
|
|
||||||
// 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)
|
||||||
|
@ -2283,8 +2290,8 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass)
|
||||||
|
|
||||||
return true;
|
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
|
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -29,6 +29,8 @@
|
||||||
#include <StorageManager/StorageManager.h>
|
#include <StorageManager/StorageManager.h>
|
||||||
#include <AP_Scripting/AP_Scripting_config.h>
|
#include <AP_Scripting/AP_Scripting_config.h>
|
||||||
|
|
||||||
|
#include "AP_Param_config.h"
|
||||||
|
|
||||||
#include "float.h"
|
#include "float.h"
|
||||||
|
|
||||||
#define AP_MAX_NAME_SIZE 16
|
#define AP_MAX_NAME_SIZE 16
|
||||||
|
@ -46,11 +48,15 @@
|
||||||
maximum size of embedded parameter file
|
maximum size of embedded parameter file
|
||||||
*/
|
*/
|
||||||
#ifndef AP_PARAM_MAX_EMBEDDED_PARAM
|
#ifndef AP_PARAM_MAX_EMBEDDED_PARAM
|
||||||
#if BOARD_FLASH_SIZE <= 1024
|
#if FORCE_APJ_DEFAULT_PARAMETERS
|
||||||
# define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
#if BOARD_FLASH_SIZE <= 1024
|
||||||
#else
|
#define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||||
# define AP_PARAM_MAX_EMBEDDED_PARAM 8192
|
#else
|
||||||
#endif
|
#define AP_PARAM_MAX_EMBEDDED_PARAM 8192
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// allow for dynamically added tables when scripting enabled
|
// allow for dynamically added tables when scripting enabled
|
||||||
|
|
|
@ -0,0 +1,13 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
|
#include <AP_Filesystem/AP_Filesystem_config.h>
|
||||||
|
|
||||||
|
#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
|
Loading…
Reference in New Issue