mirror of https://github.com/ArduPilot/ardupilot
AP_Param: setup var_info and num_vars earlier
needed for AP_HAL startup
This commit is contained in:
parent
678947c65d
commit
af12c18dea
|
@ -210,20 +210,9 @@ bool AP_Param::check_var_info(void)
|
|||
|
||||
|
||||
// setup the _var_info[] table
|
||||
bool AP_Param::setup(const struct AP_Param::Info *info, uint16_t eeprom_size)
|
||||
bool AP_Param::setup(void)
|
||||
{
|
||||
struct EEPROM_header hdr;
|
||||
uint8_t i;
|
||||
|
||||
_eeprom_size = eeprom_size;
|
||||
_var_info = info;
|
||||
|
||||
for (i=0; PGM_UINT8(&info[i].type) != AP_PARAM_NONE; i++) ;
|
||||
_num_vars = i;
|
||||
|
||||
if (!check_var_info()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
serialDebug("setup %u vars", (unsigned)_num_vars);
|
||||
|
||||
|
@ -600,6 +589,20 @@ AP_Param::find_by_index(uint16_t idx, enum ap_var_type *ptype)
|
|||
return ap;
|
||||
}
|
||||
|
||||
// Find a object by name.
|
||||
//
|
||||
AP_Param *
|
||||
AP_Param::find_object(const char *name)
|
||||
{
|
||||
for (uint8_t i=0; i<_num_vars; i++) {
|
||||
if (strcasecmp_P(name, _var_info[i].name) == 0) {
|
||||
return (AP_Param *)PGM_POINTER(&_var_info[i].ptr);
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
// Save the variable to EEPROM, if supported
|
||||
//
|
||||
bool AP_Param::save(void)
|
||||
|
@ -773,9 +776,9 @@ void AP_Param::setup_object_defaults(const void *object_pointer, const struct Gr
|
|||
|
||||
// load default values for all scalars in a sketch. This does not
|
||||
// recurse into sub-objects
|
||||
void AP_Param::setup_sketch_defaults(const struct Info *info, uint16_t eeprom_size)
|
||||
void AP_Param::setup_sketch_defaults(void)
|
||||
{
|
||||
setup(info, eeprom_size);
|
||||
setup();
|
||||
for (uint8_t i=0; i<_num_vars; i++) {
|
||||
uint8_t type = PGM_UINT8(&_var_info[i].type);
|
||||
if (type <= AP_PARAM_FLOAT) {
|
||||
|
|
|
@ -86,7 +86,19 @@ public:
|
|||
// called once at startup to setup the _var_info[] table. This
|
||||
// will also check the EEPROM header and re-initialise it if the
|
||||
// wrong version is found
|
||||
static bool setup(const struct Info *info, uint16_t eeprom_size);
|
||||
static bool setup();
|
||||
|
||||
// constructor with var_info
|
||||
AP_Param(const struct Info *info, uint16_t eeprom_size) {
|
||||
_eeprom_size = eeprom_size;
|
||||
_var_info = info;
|
||||
|
||||
uint16_t i;
|
||||
for (i=0; pgm_read_byte(&info[i].type) != AP_PARAM_NONE; i++) ;
|
||||
_num_vars = i;
|
||||
|
||||
check_var_info();
|
||||
}
|
||||
|
||||
// empty constructor
|
||||
AP_Param() {}
|
||||
|
@ -133,6 +145,14 @@ public:
|
|||
///
|
||||
static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype);
|
||||
|
||||
/// Find a object in the top level var_info table
|
||||
///
|
||||
/// If the variable has no name, it cannot be found by this interface.
|
||||
///
|
||||
/// @param name The full name of the variable to be found.
|
||||
///
|
||||
static AP_Param * find_object(const char *name);
|
||||
|
||||
/// Save the current value of the variable to EEPROM.
|
||||
///
|
||||
/// @return True if the variable was saved successfully.
|
||||
|
@ -163,7 +183,7 @@ public:
|
|||
|
||||
// load default values for all scalars in the main sketch. This
|
||||
// does not recurse into the sub-objects
|
||||
static void setup_sketch_defaults(const struct Info *info, uint16_t eeprom_size);
|
||||
static void setup_sketch_defaults(void);
|
||||
|
||||
/// Erase all variables in EEPROM.
|
||||
///
|
||||
|
|
Loading…
Reference in New Issue