38 #define ENABLE_DEBUG 1 41 # define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) 43 # define Debug(fmt, args ...) 78 { 0x55, 0x37, 0xf4, 0xa0, 0x38, 0x5d, 0x48, 0x5b },
133 if (grpinfo[i].idx == 0 && shift != 0 && !(grpinfo[i].flags &
AP_PARAM_NO_SHIFT)) {
140 return base + (63U<<shift);
142 return base + (grpinfo[i].
idx<<shift);
154 if (frame_flags == 0) {
162 uint16_t * total_size,
164 uint8_t prefix_length)
167 uint64_t used_mask = 0;
171 uint8_t idx = group_info[i].
idx;
173 Debug(
"idx too large (%u) in %s", idx, group_info[i].
name);
176 if (group_shift != 0 && idx == 0) {
180 if (used_mask & (1ULL<<idx)) {
181 Debug(
"Duplicate group idx %u for %s", idx, group_info[i].
name);
184 used_mask |= (1ULL<<idx);
188 Debug(
"double group nesting in %s", group_info[i].
name);
192 if (ginfo ==
nullptr) {
202 Debug(
"invalid type in %s", group_info[i].
name);
205 if (prefix_length + strlen(group_info[i].
name) > 16) {
206 Debug(
"suffix is too long in %s", group_info[i].name);
217 for (uint16_t i=vindex+1; i<
_num_vars; i++) {
263 if (group_info ==
nullptr) {
307 Debug(
"bad header in setup - erasing");
329 new_offset += group_info.
offset;
339 void **p = (
void **)(base + new_offset + group_info.
offset);
345 new_offset = ((ptrdiff_t)*p) - base;
356 base = *(ptrdiff_t *)info.
ptr;
357 return (base != (ptrdiff_t)0);
359 base = (ptrdiff_t)info.
ptr;
371 ptrdiff_t group_offset)
385 if (ginfo ==
nullptr) {
388 ptrdiff_t new_offset = group_offset;
395 group_id(group_info, group_base, i, group_shift),
397 if (ret !=
nullptr) {
408 *ptr = (
void*)(base + group_info[i].offset + group_offset);
429 if (group_info ==
nullptr) {
434 if (type == phdr.
type) {
452 ptrdiff_t group_offset,
453 uint32_t * group_element,
466 ptrdiff_t ofs = group_info[i].
offset + group_offset;
469 if (ginfo ==
nullptr) {
479 ptrdiff_t new_offset = group_offset;
488 group_id(group_info, group_base, i, group_shift),
495 if (info !=
nullptr) {
498 group_nesting.
level--;
499 }
else if ((ptrdiff_t)
this == base + ofs) {
500 *group_element =
group_id(group_info, group_base, i, group_shift);
501 group_ret = &group_info[i];
505 (base+ofs+(ptrdiff_t)
sizeof(
float) == (ptrdiff_t)
this ||
506 base+ofs+2*(ptrdiff_t)
sizeof(
float) == (ptrdiff_t)
this)) {
509 *idx = (((ptrdiff_t)
this) - (base+ofs))/
sizeof(float);
510 *group_element =
group_id(group_info, group_base, i, group_shift);
511 group_ret = &group_info[i];
534 if (group_info ==
nullptr) {
538 info =
find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx);
539 if (info !=
nullptr) {
542 }
else if (base == (ptrdiff_t)
this) {
547 (base+(ptrdiff_t)
sizeof(
float) == (ptrdiff_t)
this ||
548 base+2*(ptrdiff_t)
sizeof(
float) == (ptrdiff_t)
this)) {
551 *idx = (((ptrdiff_t)
this) - base)/
sizeof(
float);
562 uint32_t * group_element,
567 uint16_t i = token.
key;
577 if (group_info ==
nullptr) {
581 info =
find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx);
582 if (info !=
nullptr) {
585 }
else if (base == (ptrdiff_t)
this) {
590 (base+(ptrdiff_t)
sizeof(
float) == (ptrdiff_t)
this ||
591 base+2*(ptrdiff_t)
sizeof(
float) == (ptrdiff_t)
this)) {
594 *idx = (((ptrdiff_t)
this) - base)/
sizeof(
float);
619 Debug(
"unknown type %u\n", type);
655 uint32_t
v = *(uint32_t *)&phdr;
656 if (v == 0 || v == 0xFFFFFFFF) {
688 Debug(
"scan past end of eeprom");
700 const size_t len = strnlen(buffer, buffer_size);
701 if (len + 2 <= buffer_size) {
703 buffer[len + 1] =
static_cast<char>(
'X' + idx);
704 if (len + 3 <= buffer_size) {
721 if (info ==
nullptr) {
723 Debug(
"no info found");
726 copy_name_info(info, ginfo, group_nesting, idx, buffer, buffer_size, force_scalar);
732 uint8_t idx,
char *
buffer,
size_t buffer_size,
bool force_scalar)
const 734 strncpy(buffer, info->
name, buffer_size);
735 for (uint8_t i=0; i<group_nesting.
level; i++) {
736 uint8_t len = strnlen(buffer, buffer_size);
737 if (len < buffer_size) {
738 strncpy(&buffer[len], group_nesting.
group_ret[i]->
name, buffer_size-len);
741 if (ginfo !=
nullptr) {
742 uint8_t len = strnlen(buffer, buffer_size);
743 if (len < buffer_size) {
744 strncpy(&buffer[len], ginfo->
name, buffer_size-len);
765 if (strncasecmp(name, group_info[i].name, strlen(group_info[i].name)) != 0) {
769 if (ginfo ==
nullptr) {
772 ptrdiff_t new_offset = group_offset;
782 }
else if (strcasecmp(name, group_info[i].name) == 0) {
792 if (strncmp(name, group_info[i].name, suffix_len) == 0 &&
793 name[suffix_len] ==
'_' &&
794 (name[suffix_len+1] ==
'X' ||
795 name[suffix_len+1] ==
'Y' ||
796 name[suffix_len+1] ==
'Z')) {
801 AP_Float *
v = (AP_Float *)(base + group_info[i].offset + group_offset);
803 switch (name[suffix_len+1]) {
805 return (AP_Float *)&v[0];
807 return (AP_Float *)&v[1];
809 return (AP_Float *)&v[2];
827 if (strncmp(name,
_var_info[i].name, len) != 0) {
831 if (group_info ==
nullptr) {
841 }
else if (strcasecmp(name,
_var_info[i].name) == 0) {
874 ptrdiff_t offset, uint16_t &key)
885 if (ptr == *(
void **)(base+group_info[i].offset+offset)) {
889 }
else if (ptr == (
void *)(base+group_info[i].offset+offset)) {
893 ptrdiff_t new_offset = offset;
898 if (ginfo ==
nullptr) {
923 ptrdiff_t offset = 0;
925 if (ginfo ==
nullptr) {
942 if (strcasecmp(name,
_var_info[i].name) == 0) {
955 uint32_t group_element = 0;
961 if (info ==
nullptr) {
967 copy_name_info(info, ginfo, group_nesting, idx, name,
sizeof(name),
true);
969 uint32_t param_header_type;
970 if (ginfo !=
nullptr) {
971 param_header_type = ginfo->
type;
973 param_header_type = info->
type;
984 uint32_t group_element = 0;
991 if (info ==
nullptr) {
999 if (ginfo !=
nullptr) {
1013 ap = (
const AP_Param *)((ptrdiff_t)ap) - (idx*
sizeof(
float));
1022 copy_name_info(info, ginfo, group_nesting, idx, name,
sizeof(name),
true);
1026 if (
scan(&phdr, &ofs)) {
1032 if (ofs == (uint16_t) ~0) {
1040 if (ginfo !=
nullptr) {
1045 if (
is_equal(v1,v2) && !force_save) {
1051 (fabsf(v1-v2) < 0.0001
f*fabsf(v1)))) {
1083 if (info ==
nullptr) {
1091 if (ginfo !=
nullptr) {
1101 if (!
scan(&phdr, &ofs)) {
1108 if (ginfo !=
nullptr) {
1110 ptrdiff_t group_offset = 0;
1111 for (uint8_t i=0; i<group_nesting.
level; i++) {
1131 ap = (
AP_Param *)((ptrdiff_t)ap) - (idx*
sizeof(
float));
1146 if (info ==
nullptr) {
1154 if (ginfo !=
nullptr) {
1176 if (info ==
nullptr) {
1195 ((AP_Int8 *)ptr)->set(value);
1198 ((AP_Int16 *)ptr)->set(value);
1201 ((AP_Int32 *)ptr)->set(value);
1204 ((AP_Float *)ptr)->set(value);
1216 ptrdiff_t base = (ptrdiff_t)object_pointer;
1222 void *
ptr = (
void *)(base + group_info[i].offset);
1235 ptrdiff_t base = (ptrdiff_t)object_pointer;
1241 if (strcmp(name, group_info[i].name) == 0 && type <=
AP_PARAM_FLOAT) {
1242 void *
ptr = (
void *)(base + group_info[i].offset);
1292 if (info !=
nullptr) {
1300 Debug(
"no sentinal in load_all");
1314 #if HAL_OS_POSIX_IO == 1 1321 if (load_defaults_file(default_file, panic_on_error)) {
1322 printf(
"Loaded defaults from %s\n", default_file);
1324 printf(
"Failed to load defaults from %s\n", default_file);
1344 hal.
console->
printf(
"ERROR: Unable to find param pointer\n");
1350 ptrdiff_t new_offset = 0;
1355 if (ginfo !=
nullptr) {
1373 if (info !=
nullptr) {
1374 if ((ptrdiff_t)ptr == ((ptrdiff_t)object_pointer)+group_info[i].offset) {
1395 if (ptype !=
nullptr) {
1409 bool *found_current,
1410 uint32_t group_base,
1411 uint8_t group_shift,
1412 ptrdiff_t group_offset,
1426 if (ginfo ==
nullptr) {
1430 ptrdiff_t new_offset = group_offset;
1436 ap =
next_group(vindex, ginfo, found_current,
group_id(group_info, group_base, i, group_shift),
1438 if (ap !=
nullptr) {
1442 if (*found_current) {
1444 token->
key = vindex;
1447 if (ptype !=
nullptr) {
1457 *found_current =
true;
1462 if (ptype !=
nullptr) {
1469 ptrdiff_t ofs = base + group_info[i].
offset + group_offset;
1470 ofs +=
sizeof(float)*(token->
idx - 1u);
1483 uint16_t i = token->
key;
1484 bool found_current =
false;
1495 if (ptype !=
nullptr) {
1503 found_current =
true;
1512 if (group_info ==
nullptr) {
1516 if (ap !=
nullptr) {
1524 if (ptype !=
nullptr) {
1546 uint32_t group_element;
1551 ginfo, group_nesting, &idx);
1552 if (info && ginfo &&
1555 ((AP_Int8 *)ap)->get() == 0 &&
1565 while ((ap2 =
next(&token2, &type2)) !=
nullptr) {
1566 if (token2.
key != token->
key) {
1579 if (ap !=
nullptr && ptype !=
nullptr) {
1591 return ((AP_Int8 *)
this)->cast_to_float();
1593 return ((AP_Int16 *)
this)->cast_to_float();
1595 return ((AP_Int32 *)
this)->cast_to_float();
1597 return ((AP_Float *)
this)->cast_to_float();
1614 if (!
scan(&header, &pofs)) {
1625 #pragma GCC diagnostic push 1626 #pragma GCC diagnostic ignored "-Wformat" 1644 if (ap2 ==
nullptr) {
1657 if (ptype == info->
type &&
is_equal(scaler, 1.0
f) && flags == 0) {
1660 if (memcmp(ap2, ap,
sizeof(old_value)) != 0) {
1661 memcpy(ap2, ap,
sizeof(old_value));
1682 #pragma GCC diagnostic pop 1688 for (uint8_t i=0; i<table_size; i++) {
1717 uint8_t *new_value = group_info[i].
offset + (uint8_t *)object_pointer;
1718 memcpy(new_value, old_value,
sizeof(old_value));
1728 if (isnan(value) || isinf(value)) {
1735 float rounding_addition = 0.01f;
1739 ((AP_Float *)
this)->set(value);
1741 if (value < 0) rounding_addition = -rounding_addition;
1742 float v = value+rounding_addition;
1744 ((AP_Int32 *)
this)->set(v);
1746 if (value < 0) rounding_addition = -rounding_addition;
1747 float v = value+rounding_addition;
1749 ((AP_Int16 *)
this)->set(v);
1751 if (value < 0) rounding_addition = -rounding_addition;
1752 float v = value+rounding_addition;
1754 ((AP_Int8 *)
this)->set(v);
1764 if (line[0] ==
'#') {
1767 char *saveptr =
nullptr;
1768 char *pname = strtok_r(line,
", =\t", &saveptr);
1769 if (pname ==
nullptr) {
1775 const char *value_s = strtok_r(
nullptr,
", =\t", &saveptr);
1776 if (value_s ==
nullptr) {
1779 value = atof(value_s);
1785 #if HAL_OS_POSIX_IO == 1 1789 bool AP_Param::count_defaults_in_file(
const char *filename, uint16_t &num_defaults,
bool panic_on_error)
1791 FILE *
f =
fopen(filename,
"r");
1800 while (
fgets(line,
sizeof(line)-1, f)) {
1807 if (!
find(pname, &var_type)) {
1808 if (panic_on_error) {
1810 ::printf(
"invalid param %s in defaults file\n", pname);
1824 bool AP_Param::read_param_defaults_file(
const char *filename)
1826 FILE *
f =
fopen(filename,
"r");
1834 while (
fgets(line,
sizeof(line)-1, f)) {
1859 bool AP_Param::load_defaults_file(
const char *filename,
bool panic_on_error)
1861 if (filename ==
nullptr) {
1865 char *mutable_filename = strdup(filename);
1866 if (mutable_filename ==
nullptr) {
1867 AP_HAL::panic(
"AP_Param: Failed to allocate mutable string");
1870 uint16_t num_defaults = 0;
1871 char *saveptr =
nullptr;
1872 for (
char *pname = strtok_r(mutable_filename,
",", &saveptr);
1874 pname = strtok_r(
nullptr,
",", &saveptr)) {
1875 if (!count_defaults_in_file(pname, num_defaults, panic_on_error)) {
1876 free(mutable_filename);
1880 free(mutable_filename);
1894 mutable_filename = strdup(filename);
1895 if (mutable_filename ==
nullptr) {
1896 AP_HAL::panic(
"AP_Param: Failed to allocate mutable string");
1898 for (
char *pname = strtok_r(mutable_filename,
",", &saveptr);
1900 pname = strtok_r(
nullptr,
",", &saveptr)) {
1901 if (!read_param_defaults_file(pname)) {
1902 free(mutable_filename);
1906 free(mutable_filename);
1913 #endif // HAL_OS_POSIX_IO 1929 uint16_t n =
MIN(length,
sizeof(line)-1);
1931 if (ptr[i] ==
'\n') {
1940 memcpy(line, (
void *)ptr, i);
1946 if (line[0] ==
'#' || line[0] == 0) {
1955 if (!
find(pname, &var_type)) {
1956 if (panic_on_error) {
1957 ::printf(
"invalid param %s in defaults file\n", pname);
1958 AP_HAL::panic(
"AP_Param: Invalid param in embedded defaults");
1980 uint16_t num_defaults = 0;
2000 uint16_t n =
MIN(length,
sizeof(line)-1);
2002 if (ptr[i] ==
'\n') {
2010 memcpy(line, (
void*)ptr, i);
2016 if (line[0] ==
'#' || line[0] == 0) {
2048 return *def_value_ptr;
2071 const Vector3f &
v = ((AP_Vector3f *)
this)->get();
2075 char &name_axis = name2[strlen(name)-1];
2115 if (vp ==
nullptr) {
2120 ((AP_Int8 *)vp)->set_default(value);
2123 ((AP_Int16 *)vp)->set_default(value);
2126 ((AP_Int32 *)vp)->set_default(value);
2129 ((AP_Float *)vp)->set_default(value);
2145 if (vp ==
nullptr) {
2150 ((AP_Int8 *)vp)->set(value);
2153 ((AP_Int16 *)vp)->set(value);
2156 ((AP_Int32 *)vp)->set(value);
2159 ((AP_Float *)vp)->set(value);
2175 if (vp ==
nullptr) {
2180 ((AP_Int8 *)vp)->set_and_save(value);
2183 ((AP_Int16 *)vp)->set_and_save(value);
2186 ((AP_Int32 *)vp)->set_and_save(value);
2189 ((AP_Float *)vp)->set_and_save(value);
2198 #if AP_PARAM_KEY_DUMP 2205 void AP_Param::show(
const AP_Param *
ap,
const char *s,
2210 port->
printf(
"%s: %d\n", s, (
int)((AP_Int8 *)ap)->
get());
2213 port->
printf(
"%s: %d\n", s, (
int)((AP_Int16 *)ap)->
get());
2216 port->
printf(
"%s: %ld\n", s, (
long)((AP_Int32 *)ap)->
get());
2219 port->
printf(
"%s: %f\n", s, (
double)((AP_Float *)ap)->
get());
2233 show(ap, s, type, port);
2246 if (showKeyValues) {
2249 show(ap, token, type, port);
2252 #endif // AP_PARAM_KEY_DUMP
static void convert_parent_class(uint8_t param_key, void *object_pointer, const struct AP_Param::GroupInfo *group_info)
int printf(const char *fmt,...)
static uint16_t _frame_type_flags
static uint16_t _num_vars
bool configured_in_defaults_file(void) const
static AP_Param * find_object(const char *name)
#define AP_PARAM_FLAG_INFO_POINTER
static AP_Param * next_group(uint16_t vindex, const struct GroupInfo *group_info, bool *found_current, uint32_t group_base, uint8_t group_shift, ptrdiff_t group_offset, ParamToken *token, enum ap_var_type *ptype)
#define AP_PARAM_FLAG_ENABLE
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
#define AP_PARAM_FLAG_POINTER
const struct GroupInfo ** group_info_ptr
const struct GroupInfo ** group_info_ptr
static bool set_by_name(const char *name, float value)
static bool get_base(const struct Info &info, ptrdiff_t &base)
static bool parse_param_line(char *line, char **vname, float &value)
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
#define AP_PARAM_FLAG_NESTED_OFFSET
static void set_key(Param_header &phdr, uint16_t key)
AP_HAL::UARTDriver * console
static bool count_embedded_param_defaults(uint16_t &count, bool panic_on_error)
static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype)
static AP_Param * find_group(const char *name, uint16_t vindex, ptrdiff_t group_offset, const struct GroupInfo *group_info, enum ap_var_type *ptype)
Interface definition for the various Ground Control System.
static bool load_all(bool check_defaults_file=true)
static uint8_t buffer[SRXL_FRAMELEN_MAX]
void send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
const struct GroupInfo * group_ret[numlevels]
const struct Info * find_var_info_group(const struct GroupInfo *group_info, uint16_t vindex, uint32_t group_base, uint8_t group_shift, ptrdiff_t group_offset, uint32_t *group_element, const struct GroupInfo *&group_ret, struct GroupNesting &group_nesting, uint8_t *idx) const
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits, uint8_t prefix_length)
static uint16_t num_param_overrides
static const uint8_t _sentinal_type
uint16_t size(void) const
static const struct GroupInfo * get_group_info(const struct GroupInfo &ginfo)
get group_info pointer based on flags
static bool scan(const struct Param_header *phdr, uint16_t *pofs)
static const uint8_t _group_bits
static AP_Param * find(const char *name, enum ap_var_type *ptype)
static bool duplicate_key(uint16_t vindex, uint16_t key)
static const uint8_t numlevels
static bool set_and_save_by_name(const char *name, float value)
const AP_Param * object_ptr
static const uint8_t _group_level_shift
const struct GroupInfo * group_info
static bool adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset)
static void eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
A system for managing and storing variables that are of general interest to the system.
static const uint8_t k_EEPROM_magic1
"AP"
static uint16_t count_parameters(void)
static const uint8_t k_EEPROM_magic0
static struct param_override * param_overrides
const struct Info * find_var_info(uint32_t *group_element, const struct GroupInfo *&group_ret, struct GroupNesting &group_nesting, uint8_t *idx) const
virtual void printf(const char *,...) FMT_PRINTF(2
static bool find_key_by_pointer_group(const void *ptr, uint16_t vindex, const struct GroupInfo *group_info, ptrdiff_t offset, uint16_t &key)
void copy_name_info(const struct AP_Param::Info *info, const struct GroupInfo *ginfo, const struct GroupNesting &group_nesting, uint8_t idx, char *buffer, size_t bufferSize, bool force_scalar=false) const
#define Debug(fmt, args ...)
static void erase_all(void)
static void set_value(enum ap_var_type type, void *ptr, float def_value)
#define AP_PARAM_NO_SHIFT
static AP_Param * first(ParamToken *token, enum ap_var_type *ptype)
static bool find_key_by_pointer(const void *ptr, uint16_t &key)
#define AP_PARAM_MAX_EMBEDDED_PARAM
static const struct Info * find_by_header(struct Param_header phdr, void **ptr)
static StorageAccess _storage
void set_float(float value, enum ap_var_type var_type)
static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr)
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const
#define AP_PARAM_FRAME_TYPE_SHIFT
bool read_block(void *dst, uint16_t src, size_t n) const
static uint32_t group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift)
static void load_embedded_param_defaults(bool panic_on_error)
#define AP_PARAM_FLAG_IGNORE_ENABLE
Common definitions and utility routines for the ArduPilot libraries.
virtual const char * get_custom_defaults_file() const
static bool initialised(void)
static const param_defaults_struct param_defaults_data
float constrain_float(const float amt, const float low, const float high)
static void reload_defaults_file(bool panic_on_error=true)
volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM]
static const uint16_t _sentinal_key
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
static uint8_t type_size(enum ap_var_type type)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
const struct GroupInfo * group_info
uint32_t old_group_element
bool write_block(uint16_t dst, const void *src, size_t n) const
static void write_sentinal(uint16_t ofs)
static bool check_frame_type(uint16_t flags)
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0)
void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const
static bool is_sentinal(const Param_header &phrd)
const struct Info * find_var_info_token(const ParamToken &token, uint32_t *group_element, const struct GroupInfo *&group_ret, struct GroupNesting &group_nesting, uint8_t *idx) const
bool save(bool force_save=false)
static bool set_object_value(const void *object_pointer, const struct GroupInfo *group_info, const char *name, float value)
void panic(const char *errormsg,...) FMT_PRINTF(1
static AP_Param * next(ParamToken *token, enum ap_var_type *ptype)
static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)
static const uint8_t _sentinal_group
static uint16_t get_key(const Param_header &phdr)
static const struct Info * _var_info
static bool _hide_disabled_groups
bool configured_in_storage(void) const
char * fgets(char *str, int size, FILE *stream)
get a string from stdin See fdevopen() sets stream->put get for TTY devices
void add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx) const
static const struct Info * find_by_header_group(struct Param_header phdr, void **ptr, uint16_t vindex, const struct GroupInfo *group_info, uint32_t group_base, uint8_t group_shift, ptrdiff_t group_offset)
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0)
static bool check_var_info(void)
static void setup_sketch_defaults(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
static bool set_default_by_name(const char *name, float value)
static uint16_t _parameter_count
static const uint8_t k_EEPROM_revision
current format revision