APM:Libraries
AP_Param.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 //
20 #pragma once
21 
22 #include <stddef.h>
23 #include <string.h>
24 #include <stdint.h>
25 #include <cmath>
26 
27 #include <AP_HAL/AP_HAL.h>
29 
30 #include "float.h"
31 
32 #define AP_MAX_NAME_SIZE 16
33 
34 // optionally enable debug code for dumping keys
35 #define AP_PARAM_KEY_DUMP 0
36 
37 /*
38  maximum size of embedded parameter file
39  */
40 #ifndef AP_PARAM_MAX_EMBEDDED_PARAM
41 #define AP_PARAM_MAX_EMBEDDED_PARAM 8192
42 #endif
43 
44 /*
45  flags for variables in var_info and group tables
46  */
47 
48 // a nested offset is for subgroups that are not subclasses
49 #define AP_PARAM_FLAG_NESTED_OFFSET (1<<0)
50 
51 // a pointer variable is for dynamically allocated objects
52 #define AP_PARAM_FLAG_POINTER (1<<1)
53 
54 // an enable variable allows a whole subtree of variables to be made
55 // invisible
56 #define AP_PARAM_FLAG_ENABLE (1<<2)
57 
58 // don't shift index 0 to index 63. Use this when you know there will be
59 // no conflict with the parent
60 #define AP_PARAM_NO_SHIFT (1<<3)
61 
62 // the var_info is a pointer, allowing for dynamic definition of the var_info tree
63 #define AP_PARAM_FLAG_INFO_POINTER (1<<4)
64 
65 // ignore the enable parameter on this group
66 #define AP_PARAM_FLAG_IGNORE_ENABLE (1<<5)
67 
68 // keep all flags before the FRAME tags
69 
70 // vehicle and frame type flags, used to hide parameters when not
71 // relevent to a vehicle type. Use AP_Param::set_frame_type_flags() to
72 // enable parameters flagged in this way. frame type flags are stored
73 // in flags field, shifted by AP_PARAM_FRAME_TYPE_SHIFT.
74 #define AP_PARAM_FRAME_TYPE_SHIFT 6
75 
76 // supported frame types for parameters
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)
83 
84 // a variant of offsetof() to work around C++ restrictions.
85 // this can only be used when the offset of a variable in a object
86 // is constant and known at compile time
87 #define AP_VAROFFSET(type, element) (((ptrdiff_t)(&((const type *)1)->element))-1)
88 
89 // find the type of a variable given the class and element
90 #define AP_CLASSTYPE(clazz, element) ((uint8_t)(((const clazz *) 1)->element.vtype))
91 
92 // declare a group var_info line
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 }
94 
95 // declare a group var_info line with a frame type mask
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 )
97 
98 // declare a group var_info line with both flags and frame type mask
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) )
100 
101 // declare a group var_info line
102 #define AP_GROUPINFO(name, idx, clazz, element, def) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, 0)
103 
104 // declare a nested group entry in a group var_info
105 #define AP_NESTEDGROUPINFO(clazz, idx) { AP_PARAM_GROUP, idx, "", 0, { group_info : clazz::var_info }, 0 }
106 
107 // declare a subgroup entry in a group var_info. This is for having another arbitrary object as a member of the parameter list of
108 // an object
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 }
111 
112 // declare a second parameter table for the same object
113 #define AP_SUBGROUPEXTENSION(name, idx, clazz, vinfo) { AP_PARAM_GROUP, idx, name, 0, { group_info : clazz::vinfo }, AP_PARAM_FLAG_NESTED_OFFSET }
114 
115 // declare a pointer subgroup entry in a group var_info
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 }
117 
118 // declare a pointer subgroup entry in a group var_info with a pointer var_info
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 }
120 
121 #define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : nullptr } }
122 #define AP_VAREND { AP_PARAM_NONE, "", 0, nullptr, { group_info : nullptr } }
123 
132 };
133 
134 
139 class AP_Param
140 {
141 public:
142  // the Info and GroupInfo structures are passed by the main
143  // program in setup() to give information on how variables are
144  // named and their location in memory
145  struct GroupInfo {
146  uint8_t type; // AP_PARAM_*
147  uint8_t idx; // identifier within the group
148  const char *name;
149  ptrdiff_t offset; // offset within the object
150  union {
151  const struct GroupInfo *group_info;
152  const struct GroupInfo **group_info_ptr; // when AP_PARAM_FLAG_INFO_POINTER is set in flags
153  const float def_value;
154  };
155  uint16_t flags;
156  };
157  struct Info {
158  uint8_t type; // AP_PARAM_*
159  const char *name;
160  uint16_t key; // k_param_*
161  const void *ptr; // pointer to the variable in memory
162  union {
163  const struct GroupInfo *group_info;
164  const struct GroupInfo **group_info_ptr; // when AP_PARAM_FLAG_INFO_POINTER is set in flags
165  const float def_value;
166  };
167  uint16_t flags;
168  };
169  struct ConversionInfo {
170  uint16_t old_key; // k_param_*
171  uint32_t old_group_element; // index in old object
172  enum ap_var_type type; // AP_PARAM_*
173  const char *new_name;
174  };
175 
176  // called once at startup to setup the _var_info[] table. This
177  // will also check the EEPROM header and re-initialise it if the
178  // wrong version is found
179  static bool setup();
180 
181  // constructor with var_info
182  AP_Param(const struct Info *info)
183  {
184  _var_info = info;
185  uint16_t i;
186  for (i=0; info[i].type != AP_PARAM_NONE; i++) ;
187  _num_vars = i;
188  }
189 
190  // empty constructor
191  AP_Param() {}
192 
193  // a token used for first()/next() state
194  typedef struct {
195  uint32_t key : 9;
196  uint32_t idx : 5; // offset into array types
197  uint32_t group_element : 18;
198  } ParamToken;
199 
200 
201  // nesting structure for recursive call states
202  struct GroupNesting {
203  static const uint8_t numlevels = 2;
204  uint8_t level;
205  const struct GroupInfo *group_ret[numlevels];
206  };
207 
208  // return true if AP_Param has been initialised via setup()
209  static bool initialised(void);
210 
211  // the 'group_id' of a element of a group is the 18 bit identifier
212  // used to distinguish between this element of the group and other
213  // elements of the same group. It is calculated using a bit shift per
214  // level of nesting, so the first level of nesting gets 6 bits the 2nd
215  // level gets the next 6 bits, and the 3rd level gets the last 6
216  // bits. This limits groups to having at most 64 elements.
217  static uint32_t group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift);
218 
231  void copy_name_info(const struct AP_Param::Info *info,
232  const struct GroupInfo *ginfo,
233  const struct GroupNesting &group_nesting,
234  uint8_t idx, char *buffer, size_t bufferSize, bool force_scalar=false) const;
235 
240  void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const;
241 
250  static AP_Param * find(const char *name, enum ap_var_type *ptype);
251 
257  static bool set_default_by_name(const char *name, float value);
258 
264  static bool set_by_name(const char *name, float value);
265 
271  static bool set_and_save_by_name(const char *name, float value);
272 
280  static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token);
281 
282 
288  static bool find_key_by_pointer_group(const void *ptr, uint16_t vindex, const struct GroupInfo *group_info,
289  ptrdiff_t offset, uint16_t &key);
290  static bool find_key_by_pointer(const void *ptr, uint16_t &key);
291 
298  static AP_Param * find_object(const char *name);
299 
302  void notify() const;
303 
310  bool save(bool force_save=false);
311 
316  bool load(void);
317 
326  static bool load_all(bool check_defaults_file=true);
327 
330  static void reload_defaults_file(bool panic_on_error=true);
331 
332  static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info);
333 
334  // set a AP_Param variable to a specified value
335  static void set_value(enum ap_var_type type, void *ptr, float def_value);
336 
337  /*
338  set a parameter to a float
339  */
340  void set_float(float value, enum ap_var_type var_type);
341 
342  // load default values for scalars in a group
343  static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);
344 
345  // set a value directly in an object.
346  // return true if the name was found and set, else false.
347  // This should only be used by example code, not by mainline vehicle code
348  static bool set_object_value(const void *object_pointer,
349  const struct GroupInfo *group_info,
350  const char *name, float value);
351 
352  // load default values for all scalars in the main sketch. This
353  // does not recurse into the sub-objects
354  static void setup_sketch_defaults(void);
355 
356  // find an old parameter and return it.
357  static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value);
358 
359  // convert old vehicle parameters to new object parameters
360  static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0);
361 
362  // convert a single parameter with scaling
363  enum {
364  CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion
365  CONVERT_FLAG_FORCE=2 // store new value even if configured in eeprom already
366  };
367  static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0);
368 
369  // move old class variables for a class that was sub-classed to one that isn't
370  static void convert_parent_class(uint8_t param_key, void *object_pointer,
371  const struct AP_Param::GroupInfo *group_info);
372 
375  static void erase_all(void);
376 
382  static AP_Param * first(ParamToken *token, enum ap_var_type *ptype);
383 
386  static AP_Param * next(ParamToken *token, enum ap_var_type *ptype);
387 
390  static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype);
391 
393  float cast_to_float(enum ap_var_type type) const;
394 
395  // check var table for consistency
396  static bool check_var_info(void);
397 
398  // return true if the parameter is configured in the defaults file
399  bool configured_in_defaults_file(void) const;
400 
401  // return true if the parameter is configured in EEPROM/FRAM
402  bool configured_in_storage(void) const;
403 
404  // return true if the parameter is configured
406 
407  // count of parameters in tree
408  static uint16_t count_parameters(void);
409 
411 
412  // set frame type flags. Used to unhide frame specific parameters
413  static void set_frame_type_flags(uint16_t flags_to_set) {
414  _frame_type_flags |= flags_to_set;
415  }
416 
417  // check if a given frame type should be included
418  static bool check_frame_type(uint16_t flags);
419 
420 #if AP_PARAM_KEY_DUMP
421  static void show_all(AP_HAL::BetterStream *port, bool showKeyValues=false);
423 
425  static void show(const AP_Param *param,
426  const char *name,
427  enum ap_var_type ptype,
428  AP_HAL::BetterStream *port);
429 
431  static void show(const AP_Param *param,
432  const ParamToken &token,
433  enum ap_var_type ptype,
434  AP_HAL::BetterStream *port);
435 #endif // AP_PARAM_KEY_DUMP
436 
437 private:
443  struct EEPROM_header {
444  uint8_t magic[2];
445  uint8_t revision;
446  uint8_t spare;
447  };
448 
449 /* This header is prepended to a variable stored in EEPROM.
450  * The meaning is as follows:
451  *
452  * - key: the k_param enum value from Parameter.h in the sketch
453  *
454  * - group_element: This is zero for top level parameters. For
455  * parameters stored within an object this is divided
456  * into 3 lots of 6 bits, allowing for three levels
457  * of object to be stored in the eeprom
458  *
459  * - type: the ap_var_type value for the variable
460  */
461  struct Param_header {
462  // to get 9 bits for key we needed to split it into two parts to keep binary compatibility
463  uint32_t key_low : 8;
464  uint32_t type : 5;
465  uint32_t key_high : 1;
466  uint32_t group_element : 18;
467  };
468 
469  // number of bits in each level of nesting of groups
470  static const uint8_t _group_level_shift = 6;
471  static const uint8_t _group_bits = 18;
472 
473  static const uint16_t _sentinal_key = 0x1FF;
474  static const uint8_t _sentinal_type = 0x1F;
475  static const uint8_t _sentinal_group = 0xFF;
476 
477  static uint16_t _frame_type_flags;
478 
479  /*
480  structure for built-in defaults file that can be modified using apj_tool.py
481  */
483  char magic_str[8];
484  uint8_t param_magic[8];
485  uint16_t max_length;
486  volatile uint16_t length;
487  volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM];
488  };
490 
491 
492  static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,
493  uint8_t max_bits, uint8_t prefix_length);
494  static bool duplicate_key(uint16_t vindex, uint16_t key);
495 
496  static bool adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset);
497  static bool get_base(const struct Info &info, ptrdiff_t &base);
498 
500  static const struct GroupInfo *get_group_info(const struct GroupInfo &ginfo);
501 
503  static const struct GroupInfo *get_group_info(const struct Info &ginfo);
504 
505  const struct Info * find_var_info_group(
506  const struct GroupInfo * group_info,
507  uint16_t vindex,
508  uint32_t group_base,
509  uint8_t group_shift,
510  ptrdiff_t group_offset,
511  uint32_t * group_element,
512  const struct GroupInfo * &group_ret,
513  struct GroupNesting &group_nesting,
514  uint8_t * idx) const;
515  const struct Info * find_var_info(
516  uint32_t * group_element,
517  const struct GroupInfo * &group_ret,
518  struct GroupNesting &group_nesting,
519  uint8_t * idx) const;
520  const struct Info * find_var_info_token(const ParamToken &token,
521  uint32_t * group_element,
522  const struct GroupInfo * &group_ret,
523  struct GroupNesting &group_nesting,
524  uint8_t * idx) const;
525  static const struct Info * find_by_header_group(
526  struct Param_header phdr, void **ptr,
527  uint16_t vindex,
528  const struct GroupInfo *group_info,
529  uint32_t group_base,
530  uint8_t group_shift,
531  ptrdiff_t group_offset);
532  static const struct Info * find_by_header(
533  struct Param_header phdr,
534  void **ptr);
535  void add_vector3f_suffix(
536  char *buffer,
537  size_t buffer_size,
538  uint8_t idx) const;
539  static AP_Param * find_group(
540  const char *name,
541  uint16_t vindex,
542  ptrdiff_t group_offset,
543  const struct GroupInfo *group_info,
544  enum ap_var_type *ptype);
545  static void write_sentinal(uint16_t ofs);
546  static uint16_t get_key(const Param_header &phdr);
547  static void set_key(Param_header &phdr, uint16_t key);
548  static bool is_sentinal(const Param_header &phrd);
549  static bool scan(
550  const struct Param_header *phdr,
551  uint16_t *pofs);
552  static uint8_t type_size(enum ap_var_type type);
553  static void eeprom_write_check(
554  const void *ptr,
555  uint16_t ofs,
556  uint8_t size);
557  static AP_Param * next_group(
558  uint16_t vindex,
559  const struct GroupInfo *group_info,
560  bool *found_current,
561  uint32_t group_base,
562  uint8_t group_shift,
563  ptrdiff_t group_offset,
564  ParamToken *token,
565  enum ap_var_type *ptype);
566 
567  // find a default value given a pointer to a default value in flash
568  static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr);
569 
570  static bool parse_param_line(char *line, char **vname, float &value);
571 
572 #if HAL_OS_POSIX_IO == 1
573  /*
574  load a parameter defaults file. This happens as part of load_all()
575  */
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);
579 #endif
580 
581  /*
582  load defaults from embedded parameters
583  */
584  static bool count_embedded_param_defaults(uint16_t &count, bool panic_on_error);
585  static void load_embedded_param_defaults(bool panic_on_error);
586 
587  // send a parameter to all GCS instances
588  void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
589 
591  static uint16_t _num_vars;
592  static uint16_t _parameter_count;
593  static const struct Info * _var_info;
594 
595  /*
596  list of overridden values from load_defaults_file()
597  */
598  struct param_override {
600  float value;
601  };
603  static uint16_t num_param_overrides;
604 
605  // values filled into the EEPROM header
606  static const uint8_t k_EEPROM_magic0 = 0x50;
607  static const uint8_t k_EEPROM_magic1 = 0x41;
608  static const uint8_t k_EEPROM_revision = 6;
609 
611 };
612 
621 template<typename T, ap_var_type PT>
622 class AP_ParamT : public AP_Param
623 {
624 public:
625  static const ap_var_type vtype = PT;
626 
629  const T &get(void) const {
630  return _value;
631  }
632 
635  void set(const T &v) {
636  _value = v;
637  }
638 
641  void set_default(const T &v) {
642  if (!configured()) {
643  set(v);
644  }
645  }
646 
649  void set_and_notify(const T &v) {
650 // We do want to compare each value, even floats, since it being the same here
651 // is the result of previously setting it.
652 #pragma GCC diagnostic push
653 #pragma GCC diagnostic ignored "-Wfloat-equal"
654  if (v != _value) {
655 #pragma GCC diagnostic pop
656  set(v);
657  notify();
658  }
659  }
660 
663  bool set_and_save(const T &v) {
664  bool force = fabsf((float)(_value - v)) < FLT_EPSILON;
665  set(v);
666  return save(force);
667  }
668 
674  bool set_and_save_ifchanged(const T &v) {
675  if (v == _value) {
676  return true;
677  }
678  set(v);
679  return save(true);
680  }
681 
686  operator const T &() const {
687  return _value;
688  }
689 
692  AP_ParamT<T,PT>& operator= (const T &v) {
693  _value = v;
694  return *this;
695  }
696 
699  AP_ParamT<T,PT>& operator |=(const T &v) {
700  _value |= v;
701  return *this;
702  }
703 
704  AP_ParamT<T,PT>& operator &=(const T &v) {
705  _value &= v;
706  return *this;
707  }
708 
709  AP_ParamT<T,PT>& operator +=(const T &v) {
710  _value += v;
711  return *this;
712  }
713 
714  AP_ParamT<T,PT>& operator -=(const T &v) {
715  _value -= v;
716  return *this;
717  }
718 
721  float cast_to_float(void) const {
722  return (float)_value;
723  }
724 
725 protected:
727 };
728 
729 
738 template<typename T, ap_var_type PT>
739 class AP_ParamV : public AP_Param
740 {
741 public:
742 
743  static const ap_var_type vtype = PT;
744 
747  const T &get(void) const {
748  return _value;
749  }
750 
753  void set(const T &v) {
754  _value = v;
755  }
756 
759  void set_and_notify(const T &v) {
760  if (v != _value) {
761  set(v);
762  notify();
763  }
764  }
765 
768  bool set_and_save(const T &v) {
769  bool force = (_value != v);
770  set(v);
771  return save(force);
772  }
773 
778  operator const T &() const {
779  return _value;
780  }
781 
785  _value = v;
786  return *this;
787  }
788 
789 protected:
791 };
792 
793 
803 template<typename T, uint8_t N, ap_var_type PT>
804 class AP_ParamA : public AP_Param
805 {
806 public:
807 
808  static const ap_var_type vtype = PT;
809 
814  const T & operator[](uint8_t i) {
815  return _value[i];
816  }
817 
818  const T & operator[](int8_t i) {
819  return _value[(uint8_t)i];
820  }
821 
826  T get(uint8_t i) const {
827  if (i < N) {
828  return _value[i];
829  } else {
830  return (T)0;
831  }
832  }
833 
838  void set(uint8_t i, const T &v) {
839  if (i < N) {
840  _value[i] = v;
841  }
842  }
843 
844 protected:
845  T _value[N];
846 };
847 
848 
849 
852 // declare a scalar type
853 // _t is the base type
854 // _suffix is the suffix on the AP_* type name
855 // _pt is the enum ap_var_type type
856 #define AP_PARAMDEF(_t, _suffix, _pt) typedef AP_ParamT<_t, _pt> AP_ ## _suffix;
857 AP_PARAMDEF(float, Float, AP_PARAM_FLOAT); // defines AP_Float
858 AP_PARAMDEF(int8_t, Int8, AP_PARAM_INT8); // defines AP_Int8
859 AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16); // defines AP_Int16
860 AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32); // defines AP_Int32
861 
862 // declare a non-scalar type
863 // this is used in AP_Math.h
864 // _t is the base type
865 // _suffix is the suffix on the AP_* type name
866 // _pt is the enum ap_var_type type
867 #define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_ ## _suffix;
const char * new_name
Definition: AP_Param.h:173
static void convert_parent_class(uint8_t param_key, void *object_pointer, const struct AP_Param::GroupInfo *group_info)
Definition: AP_Param.cpp:1700
static uint16_t _frame_type_flags
Definition: AP_Param.h:477
static uint16_t _num_vars
Definition: AP_Param.h:591
bool configured_in_defaults_file(void) const
Definition: AP_Param.cpp:1169
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
AP_ParamV< T, PT > & operator=(const T &v)
Definition: AP_Param.h:784
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)
Definition: AP_Param.cpp:1408
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1335
const struct GroupInfo ** group_info_ptr
Definition: AP_Param.h:152
const struct GroupInfo ** group_info_ptr
Definition: AP_Param.h:164
static bool set_by_name(const char *name, float value)
Definition: AP_Param.cpp:2141
ap_var_type
Definition: AP_Param.h:124
uint16_t flags
Definition: AP_Param.h:167
static bool get_base(const struct Info &info, ptrdiff_t &base)
Definition: AP_Param.cpp:353
bool configured(void) const
Definition: AP_Param.h:405
static bool parse_param_line(char *line, char **vname, float &value)
Definition: AP_Param.cpp:1762
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
Definition: AP_Param.cpp:1606
static void set_key(Param_header &phdr, uint16_t key)
Definition: AP_Param.cpp:634
static bool count_embedded_param_defaults(uint16_t &count, bool panic_on_error)
Definition: AP_Param.cpp:1918
static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype)
Definition: AP_Param.cpp:1535
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)
Definition: AP_Param.cpp:757
static bool load_all(bool check_defaults_file=true)
Definition: AP_Param.cpp:1272
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
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
Definition: AP_Param.cpp:448
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits, uint8_t prefix_length)
Definition: AP_Param.cpp:161
static uint16_t num_param_overrides
Definition: AP_Param.h:603
static const uint8_t _sentinal_type
Definition: AP_Param.h:474
static const struct GroupInfo * get_group_info(const struct GroupInfo &ginfo)
get group_info pointer based on flags
Definition: AP_Param.cpp:230
static bool scan(const struct Param_header *phdr, uint16_t *pofs)
Definition: AP_Param.cpp:667
static bool setup()
Definition: AP_Param.cpp:296
static const uint8_t _group_bits
Definition: AP_Param.h:471
bool set_and_save(const T &v)
Definition: AP_Param.h:768
static AP_Param * find(const char *name, enum ap_var_type *ptype)
Definition: AP_Param.cpp:821
static bool duplicate_key(uint16_t vindex, uint16_t key)
Definition: AP_Param.cpp:215
static bool set_and_save_by_name(const char *name, float value)
Definition: AP_Param.cpp:2171
const AP_Param * object_ptr
Definition: AP_Param.h:599
const T & operator[](int8_t i)
Definition: AP_Param.h:818
static const uint8_t _group_level_shift
Definition: AP_Param.h:470
ptrdiff_t offset
Definition: AP_Param.h:149
uint16_t key
Definition: AP_Param.h:160
bool set_and_save_ifchanged(const T &v)
Definition: AP_Param.h:674
const struct GroupInfo * group_info
Definition: AP_Param.h:163
void set_and_notify(const T &v)
Definition: AP_Param.h:759
static bool adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset)
Definition: AP_Param.cpp:326
static void eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
Definition: AP_Param.cpp:90
static const uint8_t k_EEPROM_magic1
"AP"
Definition: AP_Param.h:607
static uint16_t count_parameters(void)
Definition: AP_Param.cpp:2090
static const uint8_t k_EEPROM_magic0
Definition: AP_Param.h:606
static struct param_override * param_overrides
Definition: AP_Param.h:602
const struct Info * find_var_info(uint32_t *group_element, const struct GroupInfo *&group_ret, struct GroupNesting &group_nesting, uint8_t *idx) const
Definition: AP_Param.cpp:519
static bool find_key_by_pointer_group(const void *ptr, uint16_t vindex, const struct GroupInfo *group_info, ptrdiff_t offset, uint16_t &key)
Definition: AP_Param.cpp:872
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
Definition: AP_Param.cpp:729
bool load(void)
Definition: AP_Param.cpp:1076
uint32_t group_element
Definition: AP_Param.h:466
static void erase_all(void)
Definition: AP_Param.cpp:109
static void set_value(enum ap_var_type type, void *ptr, float def_value)
Definition: AP_Param.cpp:1191
const void * ptr
Definition: AP_Param.h:161
uint8_t type
Definition: AP_Param.h:158
void notify() const
Definition: AP_Param.cpp:954
static AP_Param * first(ParamToken *token, enum ap_var_type *ptype)
Definition: AP_Param.cpp:1387
static bool find_key_by_pointer(const void *ptr, uint16_t &key)
Definition: AP_Param.cpp:912
#define AP_PARAM_MAX_EMBEDDED_PARAM
Definition: AP_Param.h:41
static const struct Info * find_by_header(struct Param_header phdr, void **ptr)
Definition: AP_Param.cpp:417
static StorageAccess _storage
Definition: AP_Param.h:590
bool set_and_save(const T &v)
Definition: AP_Param.h:663
void set_float(float value, enum ap_var_type var_type)
Definition: AP_Param.cpp:1726
const char * name
Definition: AP_Param.h:159
const char * name
Definition: AP_Param.h:148
static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr)
Definition: AP_Param.cpp:2041
void set_and_notify(const T &v)
Definition: AP_Param.h:649
static void set_frame_type_flags(uint16_t flags_to_set)
Definition: AP_Param.h:413
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const
Definition: AP_Param.cpp:2052
float v
Definition: Printf.cpp:15
uint32_t group_element
Definition: AP_Param.h:197
static uint32_t group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift)
Definition: AP_Param.cpp:131
static void load_embedded_param_defaults(bool panic_on_error)
Definition: AP_Param.cpp:1972
AP_Param(const struct Info *info)
Definition: AP_Param.h:182
static bool initialised(void)
Definition: AP_Param.cpp:315
static const param_defaults_struct param_defaults_data
Definition: AP_Param.h:489
float cast_to_float(void) const
Definition: AP_Param.h:721
static void reload_defaults_file(bool panic_on_error=true)
Definition: AP_Param.cpp:1307
static const uint16_t _sentinal_key
Definition: AP_Param.h:473
static void set_hide_disabled_groups(bool value)
Definition: AP_Param.h:410
const T & operator[](uint8_t i)
Definition: AP_Param.h:814
void set_default(const T &v)
Definition: AP_Param.h:641
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
Definition: AP_Param.cpp:1587
static uint8_t type_size(enum ap_var_type type)
Definition: AP_Param.cpp:602
const struct GroupInfo * group_info
Definition: AP_Param.h:151
uint32_t old_group_element
Definition: AP_Param.h:171
#define AP_PARAMDEF(_t, _suffix, _pt)
Definition: AP_Param.h:856
#define N
static void write_sentinal(uint16_t ofs)
Definition: AP_Param.cpp:98
static bool check_frame_type(uint16_t flags)
Definition: AP_Param.cpp:151
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0)
Definition: AP_Param.cpp:1628
#define PACKED
Definition: AP_Common.h:28
void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const
Definition: AP_Param.cpp:714
float value
static bool is_sentinal(const Param_header &phrd)
Definition: AP_Param.cpp:643
const float def_value
Definition: AP_Param.h:153
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
Definition: AP_Param.cpp:561
bool save(bool force_save=false)
Definition: AP_Param.cpp:982
static bool set_object_value(const void *object_pointer, const struct GroupInfo *group_info, const char *name, float value)
Definition: AP_Param.cpp:1231
const float def_value
Definition: AP_Param.h:165
volatile uint16_t length
Definition: AP_Param.h:486
static AP_Param * next(ParamToken *token, enum ap_var_type *ptype)
Definition: AP_Param.cpp:1481
static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)
Definition: AP_Param.cpp:856
static const uint8_t _sentinal_group
Definition: AP_Param.h:475
static uint16_t get_key(const Param_header &phdr)
Definition: AP_Param.cpp:626
static const struct Info * _var_info
Definition: AP_Param.h:593
static bool _hide_disabled_groups
Definition: AP_Param.h:610
bool configured_in_storage(void) const
Definition: AP_Param.cpp:1139
void add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx) const
Definition: AP_Param.cpp:698
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)
Definition: AP_Param.cpp:366
AP_Param()
Definition: AP_Param.h:191
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0)
Definition: AP_Param.cpp:1686
static bool check_var_info(void)
Definition: AP_Param.cpp:250
static void setup_sketch_defaults(void)
Definition: AP_Param.cpp:1254
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
static bool set_default_by_name(const char *name, float value)
Definition: AP_Param.cpp:2111
static uint16_t _parameter_count
Definition: AP_Param.h:592
static const uint8_t k_EEPROM_revision
current format revision
Definition: AP_Param.h:608