32 #define AP_MAX_NAME_SIZE 16 35 #define AP_PARAM_KEY_DUMP 0 40 #ifndef AP_PARAM_MAX_EMBEDDED_PARAM 41 #define AP_PARAM_MAX_EMBEDDED_PARAM 8192 49 #define AP_PARAM_FLAG_NESTED_OFFSET (1<<0) 52 #define AP_PARAM_FLAG_POINTER (1<<1) 56 #define AP_PARAM_FLAG_ENABLE (1<<2) 60 #define AP_PARAM_NO_SHIFT (1<<3) 63 #define AP_PARAM_FLAG_INFO_POINTER (1<<4) 66 #define AP_PARAM_FLAG_IGNORE_ENABLE (1<<5) 74 #define AP_PARAM_FRAME_TYPE_SHIFT 6 77 #define AP_PARAM_FRAME_COPTER (1<<0) 78 #define AP_PARAM_FRAME_ROVER (1<<1) 79 #define AP_PARAM_FRAME_PLANE (1<<2) 80 #define AP_PARAM_FRAME_SUB (1<<3) 81 #define AP_PARAM_FRAME_TRICOPTER (1<<4) 82 #define AP_PARAM_FRAME_HELI (1<<5) 87 #define AP_VAROFFSET(type, element) (((ptrdiff_t)(&((const type *)1)->element))-1) 90 #define AP_CLASSTYPE(clazz, element) ((uint8_t)(((const clazz *) 1)->element.vtype)) 93 #define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags) { AP_CLASSTYPE(clazz, element), idx, name, AP_VAROFFSET(clazz, element), {def_value : def}, flags } 96 #define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, (frame_flags)<<AP_PARAM_FRAME_TYPE_SHIFT ) 99 #define AP_GROUPINFO_FLAGS_FRAME(name, idx, clazz, element, def, flags, frame_flags) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags|((frame_flags)<<AP_PARAM_FRAME_TYPE_SHIFT) ) 102 #define AP_GROUPINFO(name, idx, clazz, element, def) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, 0) 105 #define AP_NESTEDGROUPINFO(clazz, idx) { AP_PARAM_GROUP, idx, "", 0, { group_info : clazz::var_info }, 0 } 109 #define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz) { AP_PARAM_GROUP, idx, name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info }, AP_PARAM_FLAG_NESTED_OFFSET } 110 #define AP_SUBGROUPINFO_FLAGS(element, name, idx, thisclazz, elclazz, flags) { AP_PARAM_GROUP, idx, name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info }, AP_PARAM_FLAG_NESTED_OFFSET | flags } 113 #define AP_SUBGROUPEXTENSION(name, idx, clazz, vinfo) { AP_PARAM_GROUP, idx, name, 0, { group_info : clazz::vinfo }, AP_PARAM_FLAG_NESTED_OFFSET } 116 #define AP_SUBGROUPPTR(element, name, idx, thisclazz, elclazz) { AP_PARAM_GROUP, idx, name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info }, AP_PARAM_FLAG_POINTER } 119 #define AP_SUBGROUPVARPTR(element, name, idx, thisclazz, var_info) { AP_PARAM_GROUP, idx, name, AP_VAROFFSET(thisclazz, element), { group_info_ptr : &var_info }, AP_PARAM_FLAG_POINTER | AP_PARAM_FLAG_INFO_POINTER } 121 #define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : nullptr } } 122 #define AP_VAREND { AP_PARAM_NONE, "", 0, nullptr, { group_info : nullptr } } 203 static const uint8_t numlevels = 2;
217 static uint32_t
group_id(
const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift);
234 uint8_t
idx,
char *
buffer,
size_t bufferSize,
bool force_scalar=
false)
const;
289 ptrdiff_t
offset, uint16_t &key);
310 bool save(
bool force_save=
false);
326 static bool load_all(
bool check_defaults_file=
true);
420 #if AP_PARAM_KEY_DUMP 425 static void show(
const AP_Param *param,
431 static void show(
const AP_Param *param,
435 #endif // AP_PARAM_KEY_DUMP 484 uint8_t param_magic[8];
493 uint8_t max_bits, uint8_t prefix_length);
497 static bool get_base(
const struct Info &info, ptrdiff_t &base);
510 ptrdiff_t group_offset,
511 uint32_t * group_element,
514 uint8_t *
idx)
const;
516 uint32_t * group_element,
519 uint8_t *
idx)
const;
521 uint32_t * group_element,
524 uint8_t *
idx)
const;
531 ptrdiff_t group_offset);
542 ptrdiff_t group_offset,
563 ptrdiff_t group_offset,
572 #if HAL_OS_POSIX_IO == 1 576 static bool count_defaults_in_file(
const char *filename, uint16_t &num_defaults,
bool panic_on_error);
577 static bool read_param_defaults_file(
const char *filename);
578 static bool load_defaults_file(
const char *filename,
bool panic_on_error);
621 template<
typename T, ap_var_type PT>
629 const T &
get(void)
const {
635 void set(
const T &
v) {
652 #pragma GCC diagnostic push 653 #pragma GCC diagnostic ignored "-Wfloat-equal" 655 #pragma GCC diagnostic pop 664 bool force = fabsf((
float)(_value - v)) < FLT_EPSILON;
686 operator const T &()
const {
722 return (
float)_value;
738 template<
typename T, ap_var_type PT>
747 const T &
get(void)
const {
753 void set(
const T &
v) {
769 bool force = (_value !=
v);
778 operator const T &()
const {
803 template<
typename T, u
int8_t N, ap_var_type PT>
819 return _value[(uint8_t)i];
826 T
get(uint8_t i)
const {
838 void set(uint8_t i,
const T &
v) {
856 #define AP_PARAMDEF(_t, _suffix, _pt) typedef AP_ParamT<_t, _pt> AP_ ## _suffix; 867 #define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_ ## _suffix;
static void convert_parent_class(uint8_t param_key, void *object_pointer, const struct AP_Param::GroupInfo *group_info)
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)
AP_ParamV< T, PT > & operator=(const T &v)
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)
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
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)
bool configured(void) const
static bool parse_param_line(char *line, char **vname, float &value)
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
static void set_key(Param_header &phdr, uint16_t key)
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)
static bool load_all(bool check_defaults_file=true)
static uint8_t buffer[SRXL_FRAMELEN_MAX]
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
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
bool set_and_save(const T &v)
static AP_Param * find(const char *name, enum ap_var_type *ptype)
static bool duplicate_key(uint16_t vindex, uint16_t key)
static bool set_and_save_by_name(const char *name, float value)
const AP_Param * object_ptr
const T & operator[](int8_t i)
static const uint8_t _group_level_shift
bool set_and_save_ifchanged(const T &v)
const struct GroupInfo * group_info
void set_and_notify(const T &v)
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)
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
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
static void erase_all(void)
static void set_value(enum ap_var_type type, void *ptr, float def_value)
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
bool set_and_save(const T &v)
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 set_and_notify(const T &v)
static void set_frame_type_flags(uint16_t flags_to_set)
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) 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)
AP_Param(const struct Info *info)
static bool initialised(void)
static const param_defaults_struct param_defaults_data
float cast_to_float(void) const
static void reload_defaults_file(bool panic_on_error=true)
static const uint16_t _sentinal_key
static void set_hide_disabled_groups(bool value)
const T & operator[](uint8_t i)
void set_default(const T &v)
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
static uint8_t type_size(enum ap_var_type type)
const struct GroupInfo * group_info
uint32_t old_group_element
#define AP_PARAMDEF(_t, _suffix, _pt)
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)
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
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