123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917 |
- #pragma once
- #include <stddef.h>
- #include <string.h>
- #include <stdint.h>
- #include <cmath>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_HAL/utility/RingBuffer.h>
- #include <StorageManager/StorageManager.h>
- #include "float.h"
- #define AP_MAX_NAME_SIZE 16
- #define AP_PARAM_KEY_DUMP 0
- #ifndef AP_PARAM_MAX_EMBEDDED_PARAM
- #define AP_PARAM_MAX_EMBEDDED_PARAM 8192
- #endif
- #define AP_PARAM_FLAG_NESTED_OFFSET (1<<0)
- #define AP_PARAM_FLAG_POINTER (1<<1)
- #define AP_PARAM_FLAG_ENABLE (1<<2)
- #define AP_PARAM_NO_SHIFT (1<<3)
- #define AP_PARAM_FLAG_INFO_POINTER (1<<4)
- #define AP_PARAM_FLAG_INTERNAL_USE_ONLY (1<<5)
- #define AP_PARAM_FRAME_TYPE_SHIFT 6
- #define AP_PARAM_FRAME_COPTER (1<<0)
- #define AP_PARAM_FRAME_ROVER (1<<1)
- #define AP_PARAM_FRAME_PLANE (1<<2)
- #define AP_PARAM_FRAME_SUB (1<<3)
- #define AP_PARAM_FRAME_TRICOPTER (1<<4)
- #define AP_PARAM_FRAME_HELI (1<<5)
- #define AP_VAROFFSET(type, element) (((ptrdiff_t)(&((const type *)1)->element))-1)
- #define AP_CLASSTYPE(clazz, element) ((uint8_t)(((const clazz *) 1)->element.vtype))
- #define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags) { AP_CLASSTYPE(clazz, element), idx, name, AP_VAROFFSET(clazz, element), {def_value : def}, flags }
- #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 )
- #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) )
- #define AP_GROUPINFO(name, idx, clazz, element, def) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, 0)
- #define AP_NESTEDGROUPINFO(clazz, idx) { AP_PARAM_GROUP, idx, "", 0, { group_info : clazz::var_info }, 0 }
- #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 }
- #define AP_SUBGROUPEXTENSION(name, idx, clazz, vinfo) { AP_PARAM_GROUP, idx, name, 0, { group_info : clazz::vinfo }, AP_PARAM_FLAG_NESTED_OFFSET }
- #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 }
- #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 }
- #define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : nullptr } }
- #define AP_VAREND { AP_PARAM_NONE, "", 0, nullptr, { group_info : nullptr } }
- enum ap_var_type {
- AP_PARAM_NONE = 0,
- AP_PARAM_INT8,
- AP_PARAM_INT16,
- AP_PARAM_INT32,
- AP_PARAM_FLOAT,
- AP_PARAM_VECTOR3F,
- AP_PARAM_GROUP
- };
- class AP_Param
- {
- public:
-
-
-
- struct GroupInfo {
- uint8_t type;
- uint8_t idx;
- const char *name;
- ptrdiff_t offset;
- union {
- const struct GroupInfo *group_info;
- const struct GroupInfo **group_info_ptr;
- const float def_value;
- };
- uint16_t flags;
- };
- struct Info {
- uint8_t type;
- const char *name;
- uint16_t key;
- const void *ptr;
- union {
- const struct GroupInfo *group_info;
- const struct GroupInfo **group_info_ptr;
- const float def_value;
- };
- uint16_t flags;
- };
- struct ConversionInfo {
- uint16_t old_key;
- uint32_t old_group_element;
- enum ap_var_type type;
- const char *new_name;
- };
-
- struct defaults_table_struct {
- const char *name;
- float value;
- };
-
-
-
- static bool setup();
-
- AP_Param(const struct Info *info)
- {
- _var_info = info;
- uint16_t i;
- for (i=0; info[i].type != AP_PARAM_NONE; i++) ;
- _num_vars = i;
- }
-
- AP_Param() {}
-
- typedef struct {
- uint32_t key : 9;
- uint32_t idx : 5;
- uint32_t group_element : 18;
- } ParamToken;
-
- struct GroupNesting {
- static const uint8_t numlevels = 2;
- uint8_t level;
- const struct GroupInfo *group_ret[numlevels];
- };
-
- static bool initialised(void);
-
-
-
-
-
-
- static uint32_t group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift);
-
-
-
-
-
-
-
-
-
-
-
-
- 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;
-
-
-
-
- void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const;
-
-
-
-
-
-
-
-
-
- static AP_Param * find(const char *name, enum ap_var_type *ptype, uint16_t *flags = nullptr);
-
-
-
-
-
- static bool set_default_by_name(const char *name, float value);
-
-
-
-
- static void set_defaults_from_table(const struct defaults_table_struct *table, uint8_t count);
-
-
-
-
-
- static bool set_by_name(const char *name, float value);
-
-
-
-
-
- static bool set_and_save_by_name(const char *name, float value);
-
-
-
-
-
-
-
- static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token);
-
-
-
-
-
- static bool find_key_by_pointer_group(const void *ptr, uint16_t vindex, const struct GroupInfo *group_info,
- ptrdiff_t offset, uint16_t &key);
- static bool find_key_by_pointer(const void *ptr, uint16_t &key);
-
-
-
-
-
-
- static AP_Param * find_object(const char *name);
-
-
- void notify() const;
-
-
-
-
-
-
- void save_sync(bool force_save=false);
-
-
- static void flush(void);
-
-
-
-
- void save(bool force_save=false);
-
-
-
-
- bool load(void);
-
-
-
-
-
-
-
-
- static bool load_all();
-
- static uint16_t storage_used() { return sentinal_offset; }
-
- static uint16_t storage_size() { return _storage.size(); }
-
-
- static void reload_defaults_file(bool last_pass);
- static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info);
-
- static void set_value(enum ap_var_type type, void *ptr, float def_value);
-
- void set_float(float value, enum ap_var_type var_type);
-
- static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);
-
-
-
- static bool set_object_value(const void *object_pointer,
- const struct GroupInfo *group_info,
- const char *name, float value);
-
-
- static void setup_sketch_defaults(void);
-
- static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value);
-
- static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0);
-
- enum {
- CONVERT_FLAG_REVERSE=1,
- CONVERT_FLAG_FORCE=2
- };
- static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0);
-
- static void convert_parent_class(uint8_t param_key, void *object_pointer,
- const struct AP_Param::GroupInfo *group_info);
-
-
- static void erase_all(void);
-
-
-
-
-
- static AP_Param * first(ParamToken *token, enum ap_var_type *ptype);
-
-
- static AP_Param * next(ParamToken *token, enum ap_var_type *ptype);
-
-
- static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype);
-
- float cast_to_float(enum ap_var_type type) const;
-
- static bool check_var_info(void);
-
- bool configured_in_defaults_file(bool &read_only) const;
-
- bool configured_in_storage(void) const;
-
- bool configured(void) const;
-
- bool is_read_only(void) const;
-
-
- static uint16_t count_parameters(void);
- static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; }
-
- static void set_frame_type_flags(uint16_t flags_to_set) {
- _frame_type_flags |= flags_to_set;
- }
-
- static bool check_frame_type(uint16_t flags);
- #if AP_PARAM_KEY_DUMP
-
- static void show_all(AP_HAL::BetterStream *port, bool showKeyValues=false);
-
- static void show(const AP_Param *param,
- const char *name,
- enum ap_var_type ptype,
- AP_HAL::BetterStream *port);
-
- static void show(const AP_Param *param,
- const ParamToken &token,
- enum ap_var_type ptype,
- AP_HAL::BetterStream *port);
- #endif
- private:
-
-
-
-
-
- struct EEPROM_header {
- uint8_t magic[2];
- uint8_t revision;
- uint8_t spare;
- };
- static uint16_t sentinal_offset;
- struct Param_header {
-
- uint32_t key_low : 8;
- uint32_t type : 5;
- uint32_t key_high : 1;
- uint32_t group_element : 18;
- };
-
- static const uint8_t _group_level_shift = 6;
- static const uint8_t _group_bits = 18;
- static const uint16_t _sentinal_key = 0x1FF;
- static const uint8_t _sentinal_type = 0x1F;
- static const uint8_t _sentinal_group = 0xFF;
- static uint16_t _frame_type_flags;
-
- #if AP_PARAM_MAX_EMBEDDED_PARAM > 0
- struct PACKED param_defaults_struct {
- char magic_str[8];
- uint8_t param_magic[8];
- uint16_t max_length;
- volatile uint16_t length;
- volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM];
- };
- static const param_defaults_struct param_defaults_data;
- #endif
- static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,
- uint8_t max_bits, uint8_t prefix_length);
- static bool duplicate_key(uint16_t vindex, uint16_t key);
- static bool adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset);
- static bool get_base(const struct Info &info, ptrdiff_t &base);
-
- static const struct GroupInfo *get_group_info(const struct GroupInfo &ginfo);
-
- static const struct GroupInfo *get_group_info(const struct Info &ginfo);
- 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;
- const struct Info * find_var_info(
- uint32_t * group_element,
- const struct GroupInfo * &group_ret,
- struct GroupNesting &group_nesting,
- uint8_t * idx) const;
- 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;
- 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 const struct Info * find_by_header(
- struct Param_header phdr,
- void **ptr);
- void add_vector3f_suffix(
- char *buffer,
- size_t buffer_size,
- uint8_t idx) const;
- 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 void write_sentinal(uint16_t ofs);
- static uint16_t get_key(const Param_header &phdr);
- static void set_key(Param_header &phdr, uint16_t key);
- static bool is_sentinal(const Param_header &phrd);
- static bool scan(
- const struct Param_header *phdr,
- uint16_t *pofs);
- static uint8_t type_size(enum ap_var_type type);
- static void eeprom_write_check(
- const void *ptr,
- uint16_t ofs,
- uint8_t size);
- 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 float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr);
- static bool parse_param_line(char *line, char **vname, float &value, bool &read_only);
- #if HAL_OS_POSIX_IO == 1
-
- static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults);
- static bool read_param_defaults_file(const char *filename, bool last_pass);
- static bool load_defaults_file(const char *filename, bool last_pass);
- #endif
-
- static bool count_embedded_param_defaults(uint16_t &count);
- static void load_embedded_param_defaults(bool last_pass);
-
- void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
- static StorageAccess _storage;
- static uint16_t _num_vars;
- static uint16_t _parameter_count;
- static const struct Info * _var_info;
-
- struct param_override {
- const AP_Param *object_ptr;
- float value;
- bool read_only;
- };
- static struct param_override *param_overrides;
- static uint16_t num_param_overrides;
- static uint16_t num_read_only;
-
- static const uint8_t k_EEPROM_magic0 = 0x50;
- static const uint8_t k_EEPROM_magic1 = 0x41;
- static const uint8_t k_EEPROM_revision = 6;
- static bool _hide_disabled_groups;
-
-
- struct PACKED param_save {
- AP_Param *param;
- bool force_save;
- };
- static ObjectBuffer<struct param_save> save_queue;
- static bool registered_save_handler;
-
- void save_io_handler(void);
- };
- template<typename T, ap_var_type PT>
- class AP_ParamT : public AP_Param
- {
- public:
- static const ap_var_type vtype = PT;
-
-
- const T &get(void) const {
- return _value;
- }
-
-
- void set(const T &v) {
- _value = v;
- }
-
-
- void set_default(const T &v) {
- if (!configured()) {
- set(v);
- }
- }
-
-
- void set_and_notify(const T &v) {
- #pragma GCC diagnostic push
- #pragma GCC diagnostic ignored "-Wfloat-equal"
- if (v != _value) {
- #pragma GCC diagnostic pop
- set(v);
- notify();
- }
- }
-
-
- void set_and_save(const T &v) {
- bool force = fabsf((float)(_value - v)) < FLT_EPSILON;
- set(v);
- save(force);
- }
-
-
-
-
-
- void set_and_save_ifchanged(const T &v) {
- if (v == _value) {
- return;
- }
- set(v);
- save(true);
- }
-
-
-
-
- operator const T &() const {
- return _value;
- }
-
-
- AP_ParamT<T,PT>& operator= (const T &v) {
- _value = v;
- return *this;
- }
-
-
- AP_ParamT<T,PT>& operator |=(const T &v) {
- _value |= v;
- return *this;
- }
- AP_ParamT<T,PT>& operator &=(const T &v) {
- _value &= v;
- return *this;
- }
- AP_ParamT<T,PT>& operator +=(const T &v) {
- _value += v;
- return *this;
- }
- AP_ParamT<T,PT>& operator -=(const T &v) {
- _value -= v;
- return *this;
- }
-
-
- float cast_to_float(void) const {
- return (float)_value;
- }
- protected:
- T _value;
- };
- template<typename T, ap_var_type PT>
- class AP_ParamV : public AP_Param
- {
- public:
- static const ap_var_type vtype = PT;
-
-
- const T &get(void) const {
- return _value;
- }
-
-
- void set(const T &v) {
- _value = v;
- }
-
-
- void set_and_notify(const T &v) {
- if (v != _value) {
- set(v);
- notify();
- }
- }
-
-
- void set_and_save(const T &v) {
- bool force = (_value != v);
- set(v);
- save(force);
- }
-
-
-
-
- operator const T &() const {
- return _value;
- }
-
-
- AP_ParamV<T,PT>& operator=(const T &v) {
- _value = v;
- return *this;
- }
- protected:
- T _value;
- };
- template<typename T, uint8_t N, ap_var_type PT>
- class AP_ParamA : public AP_Param
- {
- public:
- static const ap_var_type vtype = PT;
-
-
-
-
- const T & operator[](uint8_t i) {
- return _value[i];
- }
- const T & operator[](int8_t i) {
- return _value[(uint8_t)i];
- }
-
-
-
-
- T get(uint8_t i) const {
- if (i < N) {
- return _value[i];
- } else {
- return (T)0;
- }
- }
-
-
-
-
- void set(uint8_t i, const T &v) {
- if (i < N) {
- _value[i] = v;
- }
- }
- protected:
- T _value[N];
- };
- #define AP_PARAMDEF(_t, _suffix, _pt) typedef AP_ParamT<_t, _pt> AP_ ## _suffix;
- AP_PARAMDEF(float, Float, AP_PARAM_FLOAT);
- AP_PARAMDEF(int8_t, Int8, AP_PARAM_INT8);
- AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16);
- AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32);
- #define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_ ## _suffix;
|