AP_Param.h 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. //
  14. /// @file AP_Param.h
  15. /// @brief A system for managing and storing variables that are of
  16. /// general interest to the system.
  17. #pragma once
  18. #include <stddef.h>
  19. #include <string.h>
  20. #include <stdint.h>
  21. #include <cmath>
  22. #include <AP_HAL/AP_HAL.h>
  23. #include <AP_HAL/utility/RingBuffer.h>
  24. #include <StorageManager/StorageManager.h>
  25. #include "float.h"
  26. #define AP_MAX_NAME_SIZE 16
  27. // optionally enable debug code for dumping keys
  28. #define AP_PARAM_KEY_DUMP 0
  29. /*
  30. maximum size of embedded parameter file
  31. */
  32. #ifndef AP_PARAM_MAX_EMBEDDED_PARAM
  33. #define AP_PARAM_MAX_EMBEDDED_PARAM 8192
  34. #endif
  35. /*
  36. flags for variables in var_info and group tables
  37. */
  38. // a nested offset is for subgroups that are not subclasses
  39. #define AP_PARAM_FLAG_NESTED_OFFSET (1<<0)
  40. // a pointer variable is for dynamically allocated objects
  41. #define AP_PARAM_FLAG_POINTER (1<<1)
  42. // an enable variable allows a whole subtree of variables to be made
  43. // invisible
  44. #define AP_PARAM_FLAG_ENABLE (1<<2)
  45. // don't shift index 0 to index 63. Use this when you know there will be
  46. // no conflict with the parent
  47. #define AP_PARAM_NO_SHIFT (1<<3)
  48. // the var_info is a pointer, allowing for dynamic definition of the var_info tree
  49. #define AP_PARAM_FLAG_INFO_POINTER (1<<4)
  50. // this parameter is visible to GCS via mavlink but should never be
  51. // set by anything other than the ArduPilot code responsible for its
  52. // use.
  53. #define AP_PARAM_FLAG_INTERNAL_USE_ONLY (1<<5)
  54. // keep all flags before the FRAME tags
  55. // vehicle and frame type flags, used to hide parameters when not
  56. // relevent to a vehicle type. Use AP_Param::set_frame_type_flags() to
  57. // enable parameters flagged in this way. frame type flags are stored
  58. // in flags field, shifted by AP_PARAM_FRAME_TYPE_SHIFT.
  59. #define AP_PARAM_FRAME_TYPE_SHIFT 6
  60. // supported frame types for parameters
  61. #define AP_PARAM_FRAME_COPTER (1<<0)
  62. #define AP_PARAM_FRAME_ROVER (1<<1)
  63. #define AP_PARAM_FRAME_PLANE (1<<2)
  64. #define AP_PARAM_FRAME_SUB (1<<3)
  65. #define AP_PARAM_FRAME_TRICOPTER (1<<4)
  66. #define AP_PARAM_FRAME_HELI (1<<5)
  67. // a variant of offsetof() to work around C++ restrictions.
  68. // this can only be used when the offset of a variable in a object
  69. // is constant and known at compile time
  70. #define AP_VAROFFSET(type, element) (((ptrdiff_t)(&((const type *)1)->element))-1)
  71. // find the type of a variable given the class and element
  72. #define AP_CLASSTYPE(clazz, element) ((uint8_t)(((const clazz *) 1)->element.vtype))
  73. // declare a group var_info line
  74. #define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags) { AP_CLASSTYPE(clazz, element), idx, name, AP_VAROFFSET(clazz, element), {def_value : def}, flags }
  75. // declare a group var_info line with a frame type mask
  76. #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 )
  77. // declare a group var_info line with both flags and frame type mask
  78. #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) )
  79. // declare a group var_info line
  80. #define AP_GROUPINFO(name, idx, clazz, element, def) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, 0)
  81. // declare a nested group entry in a group var_info
  82. #define AP_NESTEDGROUPINFO(clazz, idx) { AP_PARAM_GROUP, idx, "", 0, { group_info : clazz::var_info }, 0 }
  83. // declare a subgroup entry in a group var_info. This is for having another arbitrary object as a member of the parameter list of
  84. // an object
  85. #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 }
  86. // declare a second parameter table for the same object
  87. #define AP_SUBGROUPEXTENSION(name, idx, clazz, vinfo) { AP_PARAM_GROUP, idx, name, 0, { group_info : clazz::vinfo }, AP_PARAM_FLAG_NESTED_OFFSET }
  88. // declare a pointer subgroup entry in a group var_info
  89. #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 }
  90. // declare a pointer subgroup entry in a group var_info with a pointer var_info
  91. #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 }
  92. #define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : nullptr } }
  93. #define AP_VAREND { AP_PARAM_NONE, "", 0, nullptr, { group_info : nullptr } }
  94. enum ap_var_type {
  95. AP_PARAM_NONE = 0,
  96. AP_PARAM_INT8,
  97. AP_PARAM_INT16,
  98. AP_PARAM_INT32,
  99. AP_PARAM_FLOAT,
  100. AP_PARAM_VECTOR3F,
  101. AP_PARAM_GROUP
  102. };
  103. /// Base class for variables.
  104. ///
  105. /// Provides naming and lookup services for variables.
  106. ///
  107. class AP_Param
  108. {
  109. public:
  110. // the Info and GroupInfo structures are passed by the main
  111. // program in setup() to give information on how variables are
  112. // named and their location in memory
  113. struct GroupInfo {
  114. uint8_t type; // AP_PARAM_*
  115. uint8_t idx; // identifier within the group
  116. const char *name;
  117. ptrdiff_t offset; // offset within the object
  118. union {
  119. const struct GroupInfo *group_info;
  120. const struct GroupInfo **group_info_ptr; // when AP_PARAM_FLAG_INFO_POINTER is set in flags
  121. const float def_value;
  122. };
  123. uint16_t flags;
  124. };
  125. struct Info {
  126. uint8_t type; // AP_PARAM_*
  127. const char *name;
  128. uint16_t key; // k_param_*
  129. const void *ptr; // pointer to the variable in memory
  130. union {
  131. const struct GroupInfo *group_info;
  132. const struct GroupInfo **group_info_ptr; // when AP_PARAM_FLAG_INFO_POINTER is set in flags
  133. const float def_value;
  134. };
  135. uint16_t flags;
  136. };
  137. struct ConversionInfo {
  138. uint16_t old_key; // k_param_*
  139. uint32_t old_group_element; // index in old object
  140. enum ap_var_type type; // AP_PARAM_*
  141. const char *new_name;
  142. };
  143. // param default table element
  144. struct defaults_table_struct {
  145. const char *name; // parameter name
  146. float value; // parameter value
  147. };
  148. // called once at startup to setup the _var_info[] table. This
  149. // will also check the EEPROM header and re-initialise it if the
  150. // wrong version is found
  151. static bool setup();
  152. // constructor with var_info
  153. AP_Param(const struct Info *info)
  154. {
  155. _var_info = info;
  156. uint16_t i;
  157. for (i=0; info[i].type != AP_PARAM_NONE; i++) ;
  158. _num_vars = i;
  159. }
  160. // empty constructor
  161. AP_Param() {}
  162. // a token used for first()/next() state
  163. typedef struct {
  164. uint32_t key : 9;
  165. uint32_t idx : 5; // offset into array types
  166. uint32_t group_element : 18;
  167. } ParamToken;
  168. // nesting structure for recursive call states
  169. struct GroupNesting {
  170. static const uint8_t numlevels = 2;
  171. uint8_t level;
  172. const struct GroupInfo *group_ret[numlevels];
  173. };
  174. // return true if AP_Param has been initialised via setup()
  175. static bool initialised(void);
  176. // the 'group_id' of a element of a group is the 18 bit identifier
  177. // used to distinguish between this element of the group and other
  178. // elements of the same group. It is calculated using a bit shift per
  179. // level of nesting, so the first level of nesting gets 6 bits the 2nd
  180. // level gets the next 6 bits, and the 3rd level gets the last 6
  181. // bits. This limits groups to having at most 64 elements.
  182. static uint32_t group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift);
  183. /// Copy the variable's name, prefixed by any containing group name, to a
  184. /// buffer.
  185. ///
  186. /// If the variable has no name, the buffer will contain an empty string.
  187. ///
  188. /// Note that if the combination of names is larger than the buffer, the
  189. /// result in the buffer will be truncated.
  190. ///
  191. /// @param token token giving current variable
  192. /// @param buffer The destination buffer
  193. /// @param bufferSize Total size of the destination buffer.
  194. ///
  195. void copy_name_info(const struct AP_Param::Info *info,
  196. const struct GroupInfo *ginfo,
  197. const struct GroupNesting &group_nesting,
  198. uint8_t idx, char *buffer, size_t bufferSize, bool force_scalar=false) const;
  199. /// Copy the variable's name, prefixed by any containing group name, to a
  200. /// buffer.
  201. ///
  202. /// Uses token to look up AP_Param::Info for the variable
  203. void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const;
  204. /// Find a variable by name.
  205. ///
  206. /// If the variable has no name, it cannot be found by this interface.
  207. ///
  208. /// @param name The full name of the variable to be found.
  209. /// @param flags If non-null will be filled with parameter flags
  210. /// @return A pointer to the variable, or nullptr if
  211. /// it does not exist.
  212. ///
  213. static AP_Param * find(const char *name, enum ap_var_type *ptype, uint16_t *flags = nullptr);
  214. /// set a default value by name
  215. ///
  216. /// @param name The full name of the variable to be found.
  217. /// @param value The default value
  218. /// @return true if the variable is found
  219. static bool set_default_by_name(const char *name, float value);
  220. /// set parameter defaults from a defaults_table_struct
  221. ///
  222. /// @param table pointer to array of defaults_table_struct structures
  223. /// @param count number of elements in table array
  224. static void set_defaults_from_table(const struct defaults_table_struct *table, uint8_t count);
  225. /// set a value by name
  226. ///
  227. /// @param name The full name of the variable to be found.
  228. /// @param value The new value
  229. /// @return true if the variable is found
  230. static bool set_by_name(const char *name, float value);
  231. /// set and save a value by name
  232. ///
  233. /// @param name The full name of the variable to be found.
  234. /// @param value The new value
  235. /// @return true if the variable is found
  236. static bool set_and_save_by_name(const char *name, float value);
  237. /// Find a variable by index.
  238. ///
  239. ///
  240. /// @param idx The index of the variable
  241. /// @return A pointer to the variable, or nullptr if
  242. /// it does not exist.
  243. ///
  244. static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token);
  245. /// Find a variable by pointer
  246. ///
  247. ///
  248. /// @param p Pointer to variable
  249. /// @return key for variable
  250. static bool find_key_by_pointer_group(const void *ptr, uint16_t vindex, const struct GroupInfo *group_info,
  251. ptrdiff_t offset, uint16_t &key);
  252. static bool find_key_by_pointer(const void *ptr, uint16_t &key);
  253. /// Find a object in the top level var_info table
  254. ///
  255. /// If the variable has no name, it cannot be found by this interface.
  256. ///
  257. /// @param name The full name of the variable to be found.
  258. ///
  259. static AP_Param * find_object(const char *name);
  260. /// Notify GCS of current parameter value
  261. ///
  262. void notify() const;
  263. /// Save the current value of the variable to storage, synchronous API
  264. ///
  265. /// @param force_save If true then force save even if default
  266. ///
  267. /// @return True if the variable was saved successfully.
  268. ///
  269. void save_sync(bool force_save=false);
  270. /// flush all pending parameter saves
  271. /// used on reboot
  272. static void flush(void);
  273. /// Save the current value of the variable to storage, async interface
  274. ///
  275. /// @param force_save If true then force save even if default
  276. ///
  277. void save(bool force_save=false);
  278. /// Load the variable from EEPROM.
  279. ///
  280. /// @return True if the variable was loaded successfully.
  281. ///
  282. bool load(void);
  283. /// Load all variables from EEPROM
  284. ///
  285. /// This function performs a best-efforts attempt to load all
  286. /// of the variables from EEPROM. If some fail to load, their
  287. /// values will remain as they are.
  288. ///
  289. /// @return False if any variable failed to load
  290. ///
  291. static bool load_all();
  292. // returns storage space used:
  293. static uint16_t storage_used() { return sentinal_offset; }
  294. // returns storage space :
  295. static uint16_t storage_size() { return _storage.size(); }
  296. /// reoad the hal.util defaults file. Called after pointer parameters have been allocated
  297. ///
  298. static void reload_defaults_file(bool last_pass);
  299. static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info);
  300. // set a AP_Param variable to a specified value
  301. static void set_value(enum ap_var_type type, void *ptr, float def_value);
  302. /*
  303. set a parameter to a float
  304. */
  305. void set_float(float value, enum ap_var_type var_type);
  306. // load default values for scalars in a group
  307. static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);
  308. // set a value directly in an object.
  309. // return true if the name was found and set, else false.
  310. // This should only be used by example code, not by mainline vehicle code
  311. static bool set_object_value(const void *object_pointer,
  312. const struct GroupInfo *group_info,
  313. const char *name, float value);
  314. // load default values for all scalars in the main sketch. This
  315. // does not recurse into the sub-objects
  316. static void setup_sketch_defaults(void);
  317. // find an old parameter and return it.
  318. static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value);
  319. // convert old vehicle parameters to new object parameters
  320. static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0);
  321. // convert a single parameter with scaling
  322. enum {
  323. CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion
  324. CONVERT_FLAG_FORCE=2 // store new value even if configured in eeprom already
  325. };
  326. static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0);
  327. // move old class variables for a class that was sub-classed to one that isn't
  328. static void convert_parent_class(uint8_t param_key, void *object_pointer,
  329. const struct AP_Param::GroupInfo *group_info);
  330. /// Erase all variables in EEPROM.
  331. ///
  332. static void erase_all(void);
  333. /// Returns the first variable
  334. ///
  335. /// @return The first variable in _var_info, or nullptr if
  336. /// there are none.
  337. ///
  338. static AP_Param * first(ParamToken *token, enum ap_var_type *ptype);
  339. /// Returns the next variable in _var_info, recursing into groups
  340. /// as needed
  341. static AP_Param * next(ParamToken *token, enum ap_var_type *ptype);
  342. /// Returns the next scalar variable in _var_info, recursing into groups
  343. /// as needed
  344. static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype);
  345. /// cast a variable to a float given its type
  346. float cast_to_float(enum ap_var_type type) const;
  347. // check var table for consistency
  348. static bool check_var_info(void);
  349. // return true if the parameter is configured in the defaults file
  350. bool configured_in_defaults_file(bool &read_only) const;
  351. // return true if the parameter is configured in EEPROM/FRAM
  352. bool configured_in_storage(void) const;
  353. // return true if the parameter is configured
  354. bool configured(void) const;
  355. // return true if the parameter is read-only
  356. bool is_read_only(void) const;
  357. // count of parameters in tree
  358. static uint16_t count_parameters(void);
  359. static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; }
  360. // set frame type flags. Used to unhide frame specific parameters
  361. static void set_frame_type_flags(uint16_t flags_to_set) {
  362. _frame_type_flags |= flags_to_set;
  363. }
  364. // check if a given frame type should be included
  365. static bool check_frame_type(uint16_t flags);
  366. #if AP_PARAM_KEY_DUMP
  367. /// print the value of all variables
  368. static void show_all(AP_HAL::BetterStream *port, bool showKeyValues=false);
  369. /// print the value of one variable
  370. static void show(const AP_Param *param,
  371. const char *name,
  372. enum ap_var_type ptype,
  373. AP_HAL::BetterStream *port);
  374. /// print the value of one variable
  375. static void show(const AP_Param *param,
  376. const ParamToken &token,
  377. enum ap_var_type ptype,
  378. AP_HAL::BetterStream *port);
  379. #endif // AP_PARAM_KEY_DUMP
  380. private:
  381. /// EEPROM header
  382. ///
  383. /// This structure is placed at the head of the EEPROM to indicate
  384. /// that the ROM is formatted for AP_Param.
  385. ///
  386. struct EEPROM_header {
  387. uint8_t magic[2];
  388. uint8_t revision;
  389. uint8_t spare;
  390. };
  391. static uint16_t sentinal_offset;
  392. /* This header is prepended to a variable stored in EEPROM.
  393. * The meaning is as follows:
  394. *
  395. * - key: the k_param enum value from Parameter.h in the sketch
  396. *
  397. * - group_element: This is zero for top level parameters. For
  398. * parameters stored within an object this is divided
  399. * into 3 lots of 6 bits, allowing for three levels
  400. * of object to be stored in the eeprom
  401. *
  402. * - type: the ap_var_type value for the variable
  403. */
  404. struct Param_header {
  405. // to get 9 bits for key we needed to split it into two parts to keep binary compatibility
  406. uint32_t key_low : 8;
  407. uint32_t type : 5;
  408. uint32_t key_high : 1;
  409. uint32_t group_element : 18;
  410. };
  411. // number of bits in each level of nesting of groups
  412. static const uint8_t _group_level_shift = 6;
  413. static const uint8_t _group_bits = 18;
  414. static const uint16_t _sentinal_key = 0x1FF;
  415. static const uint8_t _sentinal_type = 0x1F;
  416. static const uint8_t _sentinal_group = 0xFF;
  417. static uint16_t _frame_type_flags;
  418. /*
  419. structure for built-in defaults file that can be modified using apj_tool.py
  420. */
  421. #if AP_PARAM_MAX_EMBEDDED_PARAM > 0
  422. struct PACKED param_defaults_struct {
  423. char magic_str[8];
  424. uint8_t param_magic[8];
  425. uint16_t max_length;
  426. volatile uint16_t length;
  427. volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM];
  428. };
  429. static const param_defaults_struct param_defaults_data;
  430. #endif
  431. static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,
  432. uint8_t max_bits, uint8_t prefix_length);
  433. static bool duplicate_key(uint16_t vindex, uint16_t key);
  434. static bool adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset);
  435. static bool get_base(const struct Info &info, ptrdiff_t &base);
  436. /// get group_info pointer based on flags
  437. static const struct GroupInfo *get_group_info(const struct GroupInfo &ginfo);
  438. /// get group_info pointer based on flags
  439. static const struct GroupInfo *get_group_info(const struct Info &ginfo);
  440. const struct Info * find_var_info_group(
  441. const struct GroupInfo * group_info,
  442. uint16_t vindex,
  443. uint32_t group_base,
  444. uint8_t group_shift,
  445. ptrdiff_t group_offset,
  446. uint32_t * group_element,
  447. const struct GroupInfo * &group_ret,
  448. struct GroupNesting &group_nesting,
  449. uint8_t * idx) const;
  450. const struct Info * find_var_info(
  451. uint32_t * group_element,
  452. const struct GroupInfo * &group_ret,
  453. struct GroupNesting &group_nesting,
  454. uint8_t * idx) const;
  455. const struct Info * find_var_info_token(const ParamToken &token,
  456. uint32_t * group_element,
  457. const struct GroupInfo * &group_ret,
  458. struct GroupNesting &group_nesting,
  459. uint8_t * idx) const;
  460. static const struct Info * find_by_header_group(
  461. struct Param_header phdr, void **ptr,
  462. uint16_t vindex,
  463. const struct GroupInfo *group_info,
  464. uint32_t group_base,
  465. uint8_t group_shift,
  466. ptrdiff_t group_offset);
  467. static const struct Info * find_by_header(
  468. struct Param_header phdr,
  469. void **ptr);
  470. void add_vector3f_suffix(
  471. char *buffer,
  472. size_t buffer_size,
  473. uint8_t idx) const;
  474. static AP_Param * find_group(
  475. const char *name,
  476. uint16_t vindex,
  477. ptrdiff_t group_offset,
  478. const struct GroupInfo *group_info,
  479. enum ap_var_type *ptype);
  480. static void write_sentinal(uint16_t ofs);
  481. static uint16_t get_key(const Param_header &phdr);
  482. static void set_key(Param_header &phdr, uint16_t key);
  483. static bool is_sentinal(const Param_header &phrd);
  484. static bool scan(
  485. const struct Param_header *phdr,
  486. uint16_t *pofs);
  487. static uint8_t type_size(enum ap_var_type type);
  488. static void eeprom_write_check(
  489. const void *ptr,
  490. uint16_t ofs,
  491. uint8_t size);
  492. static AP_Param * next_group(
  493. uint16_t vindex,
  494. const struct GroupInfo *group_info,
  495. bool *found_current,
  496. uint32_t group_base,
  497. uint8_t group_shift,
  498. ptrdiff_t group_offset,
  499. ParamToken *token,
  500. enum ap_var_type *ptype);
  501. // find a default value given a pointer to a default value in flash
  502. static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr);
  503. static bool parse_param_line(char *line, char **vname, float &value, bool &read_only);
  504. #if HAL_OS_POSIX_IO == 1
  505. /*
  506. load a parameter defaults file. This happens as part of load_all()
  507. */
  508. static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults);
  509. static bool read_param_defaults_file(const char *filename, bool last_pass);
  510. static bool load_defaults_file(const char *filename, bool last_pass);
  511. #endif
  512. /*
  513. load defaults from embedded parameters
  514. */
  515. static bool count_embedded_param_defaults(uint16_t &count);
  516. static void load_embedded_param_defaults(bool last_pass);
  517. // send a parameter to all GCS instances
  518. void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
  519. static StorageAccess _storage;
  520. static uint16_t _num_vars;
  521. static uint16_t _parameter_count;
  522. static const struct Info * _var_info;
  523. /*
  524. list of overridden values from load_defaults_file()
  525. */
  526. struct param_override {
  527. const AP_Param *object_ptr;
  528. float value;
  529. bool read_only; // param is marked @READONLY
  530. };
  531. static struct param_override *param_overrides;
  532. static uint16_t num_param_overrides;
  533. static uint16_t num_read_only;
  534. // values filled into the EEPROM header
  535. static const uint8_t k_EEPROM_magic0 = 0x50;
  536. static const uint8_t k_EEPROM_magic1 = 0x41; ///< "AP"
  537. static const uint8_t k_EEPROM_revision = 6; ///< current format revision
  538. static bool _hide_disabled_groups;
  539. // support for background saving of parameters. We pack it to reduce memory for the
  540. // queue
  541. struct PACKED param_save {
  542. AP_Param *param;
  543. bool force_save;
  544. };
  545. static ObjectBuffer<struct param_save> save_queue;
  546. static bool registered_save_handler;
  547. // background function for saving parameters
  548. void save_io_handler(void);
  549. };
  550. /// Template class for scalar variables.
  551. ///
  552. /// Objects of this type have a value, and can be treated in many ways as though they
  553. /// were the value.
  554. ///
  555. /// @tparam T The scalar type of the variable
  556. /// @tparam PT The AP_PARAM_* type
  557. ///
  558. template<typename T, ap_var_type PT>
  559. class AP_ParamT : public AP_Param
  560. {
  561. public:
  562. static const ap_var_type vtype = PT;
  563. /// Value getter
  564. ///
  565. const T &get(void) const {
  566. return _value;
  567. }
  568. /// Value setter
  569. ///
  570. void set(const T &v) {
  571. _value = v;
  572. }
  573. /// Sets if the parameter is unconfigured
  574. ///
  575. void set_default(const T &v) {
  576. if (!configured()) {
  577. set(v);
  578. }
  579. }
  580. /// Value setter - set value, tell GCS
  581. ///
  582. void set_and_notify(const T &v) {
  583. // We do want to compare each value, even floats, since it being the same here
  584. // is the result of previously setting it.
  585. #pragma GCC diagnostic push
  586. #pragma GCC diagnostic ignored "-Wfloat-equal"
  587. if (v != _value) {
  588. #pragma GCC diagnostic pop
  589. set(v);
  590. notify();
  591. }
  592. }
  593. /// Combined set and save
  594. ///
  595. void set_and_save(const T &v) {
  596. bool force = fabsf((float)(_value - v)) < FLT_EPSILON;
  597. set(v);
  598. save(force);
  599. }
  600. /// Combined set and save, but only does the save if the value if
  601. /// different from the current ram value, thus saving us a
  602. /// scan(). This should only be used where we have not set() the
  603. /// value separately, as otherwise the value in EEPROM won't be
  604. /// updated correctly.
  605. void set_and_save_ifchanged(const T &v) {
  606. if (v == _value) {
  607. return;
  608. }
  609. set(v);
  610. save(true);
  611. }
  612. /// Conversion to T returns a reference to the value.
  613. ///
  614. /// This allows the class to be used in many situations where the value would be legal.
  615. ///
  616. operator const T &() const {
  617. return _value;
  618. }
  619. /// Copy assignment from T is equivalent to ::set.
  620. ///
  621. AP_ParamT<T,PT>& operator= (const T &v) {
  622. _value = v;
  623. return *this;
  624. }
  625. /// bit ops on parameters
  626. ///
  627. AP_ParamT<T,PT>& operator |=(const T &v) {
  628. _value |= v;
  629. return *this;
  630. }
  631. AP_ParamT<T,PT>& operator &=(const T &v) {
  632. _value &= v;
  633. return *this;
  634. }
  635. AP_ParamT<T,PT>& operator +=(const T &v) {
  636. _value += v;
  637. return *this;
  638. }
  639. AP_ParamT<T,PT>& operator -=(const T &v) {
  640. _value -= v;
  641. return *this;
  642. }
  643. /// AP_ParamT types can implement AP_Param::cast_to_float
  644. ///
  645. float cast_to_float(void) const {
  646. return (float)_value;
  647. }
  648. protected:
  649. T _value;
  650. };
  651. /// Template class for non-scalar variables.
  652. ///
  653. /// Objects of this type have a value, and can be treated in many ways as though they
  654. /// were the value.
  655. ///
  656. /// @tparam T The scalar type of the variable
  657. /// @tparam PT AP_PARAM_* type
  658. ///
  659. template<typename T, ap_var_type PT>
  660. class AP_ParamV : public AP_Param
  661. {
  662. public:
  663. static const ap_var_type vtype = PT;
  664. /// Value getter
  665. ///
  666. const T &get(void) const {
  667. return _value;
  668. }
  669. /// Value setter
  670. ///
  671. void set(const T &v) {
  672. _value = v;
  673. }
  674. /// Value setter - set value, tell GCS
  675. ///
  676. void set_and_notify(const T &v) {
  677. if (v != _value) {
  678. set(v);
  679. notify();
  680. }
  681. }
  682. /// Combined set and save
  683. ///
  684. void set_and_save(const T &v) {
  685. bool force = (_value != v);
  686. set(v);
  687. save(force);
  688. }
  689. /// Conversion to T returns a reference to the value.
  690. ///
  691. /// This allows the class to be used in many situations where the value would be legal.
  692. ///
  693. operator const T &() const {
  694. return _value;
  695. }
  696. /// Copy assignment from T is equivalent to ::set.
  697. ///
  698. AP_ParamV<T,PT>& operator=(const T &v) {
  699. _value = v;
  700. return *this;
  701. }
  702. protected:
  703. T _value;
  704. };
  705. /// Template class for array variables.
  706. ///
  707. /// Objects created using this template behave like arrays of the type T,
  708. /// but are stored like single variables.
  709. ///
  710. /// @tparam T The scalar type of the variable
  711. /// @tparam N number of elements
  712. /// @tparam PT the AP_PARAM_* type
  713. ///
  714. template<typename T, uint8_t N, ap_var_type PT>
  715. class AP_ParamA : public AP_Param
  716. {
  717. public:
  718. static const ap_var_type vtype = PT;
  719. /// Array operator accesses members.
  720. ///
  721. /// @note It would be nice to range-check i here, but then what would we return?
  722. ///
  723. const T & operator[](uint8_t i) {
  724. return _value[i];
  725. }
  726. const T & operator[](int8_t i) {
  727. return _value[(uint8_t)i];
  728. }
  729. /// Value getter
  730. ///
  731. /// @note Returns zero for index values out of range.
  732. ///
  733. T get(uint8_t i) const {
  734. if (i < N) {
  735. return _value[i];
  736. } else {
  737. return (T)0;
  738. }
  739. }
  740. /// Value setter
  741. ///
  742. /// @note Attempts to set an index out of range are discarded.
  743. ///
  744. void set(uint8_t i, const T &v) {
  745. if (i < N) {
  746. _value[i] = v;
  747. }
  748. }
  749. protected:
  750. T _value[N];
  751. };
  752. /// Convenience macro for defining instances of the AP_ParamT template.
  753. ///
  754. // declare a scalar type
  755. // _t is the base type
  756. // _suffix is the suffix on the AP_* type name
  757. // _pt is the enum ap_var_type type
  758. #define AP_PARAMDEF(_t, _suffix, _pt) typedef AP_ParamT<_t, _pt> AP_ ## _suffix;
  759. AP_PARAMDEF(float, Float, AP_PARAM_FLOAT); // defines AP_Float
  760. AP_PARAMDEF(int8_t, Int8, AP_PARAM_INT8); // defines AP_Int8
  761. AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16); // defines AP_Int16
  762. AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32); // defines AP_Int32
  763. // declare a non-scalar type
  764. // this is used in AP_Math.h
  765. // _t is the base type
  766. // _suffix is the suffix on the AP_* type name
  767. // _pt is the enum ap_var_type type
  768. #define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_ ## _suffix;