APM:Libraries
AP_Param.cpp
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 //
17 //
18 
19 // total up and check overflow
20 // check size of group var_info
21 
24 #include "AP_Param.h"
25 
26 #include <cmath>
27 #include <string.h>
28 
29 #include <AP_Common/AP_Common.h>
30 #include <AP_HAL/AP_HAL.h>
31 #include <AP_Math/AP_Math.h>
32 #include <GCS_MAVLink/GCS.h>
34 #include <stdio.h>
35 
36 extern const AP_HAL::HAL &hal;
37 
38 #define ENABLE_DEBUG 1
39 
40 #if ENABLE_DEBUG
41  # define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
42 #else
43  # define Debug(fmt, args ...)
44 #endif
45 
46 // Note about AP_Vector3f handling.
47 // The code has special cases for AP_Vector3f to allow it to be viewed
48 // as both a single 3 element vector and as a set of 3 AP_Float
49 // variables. This is done to make it possible for MAVLink to see
50 // vectors as parameters, which allows users to save their compass
51 // offsets in MAVLink parameter files. The code involves quite a few
52 // special cases which could be generalised to any vector/matrix type
53 // if we end up needing this behaviour for other than AP_Vector3f
54 
55 
56 // static member variables for AP_Param.
57 //
58 
59 // number of rows in the _var_info[] table
60 uint16_t AP_Param::_num_vars;
61 
62 // cached parameter count
64 
65 // storage and naming information about all types that can be saved
67 
70 
71 /*
72  this holds default parameters in the normal NAME=value form for a
73  parameter file. It can be manipulated by apj_tool.py to change the
74  defaults on a binary without recompiling
75  */
77  "PARMDEF",
78  { 0x55, 0x37, 0xf4, 0xa0, 0x38, 0x5d, 0x48, 0x5b },
80  0
81 };
82 
83 // storage object
85 
86 // flags indicating frame type
88 
89 // write to EEPROM
90 void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
91 {
92  _storage.write_block(ofs, ptr, size);
93 }
94 
96 
97 // write a sentinal value at the given offset
98 void AP_Param::write_sentinal(uint16_t ofs)
99 {
100  struct Param_header phdr;
101  phdr.type = _sentinal_type;
102  set_key(phdr, _sentinal_key);
104  eeprom_write_check(&phdr, ofs, sizeof(phdr));
105 }
106 
107 // erase all EEPROM variables by re-writing the header and adding
108 // a sentinal
110 {
111  struct EEPROM_header hdr;
112 
113  // write the header
114  hdr.magic[0] = k_EEPROM_magic0;
115  hdr.magic[1] = k_EEPROM_magic1;
117  hdr.spare = 0;
118  eeprom_write_check(&hdr, 0, sizeof(hdr));
119 
120  // add a sentinal directly after the header
121  write_sentinal(sizeof(struct EEPROM_header));
122 }
123 
124 /* the 'group_id' of a element of a group is the 18 bit identifier
125  used to distinguish between this element of the group and other
126  elements of the same group. It is calculated using a bit shift per
127  level of nesting, so the first level of nesting gets 6 bits the 2nd
128  level gets the next 6 bits, and the 3rd level gets the last 6
129  bits. This limits groups to having at most 64 elements.
130 */
131 uint32_t AP_Param::group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift)
132 {
133  if (grpinfo[i].idx == 0 && shift != 0 && !(grpinfo[i].flags & AP_PARAM_NO_SHIFT)) {
134  /*
135  this is a special case for a bug in the original design. An
136  idx of 0 shifted by n bits is still zero, which makes it
137  indistinguishable from a different parameter. This can lead
138  to parameter loops. We use index 63 for that case.
139  */
140  return base + (63U<<shift);
141  }
142  return base + (grpinfo[i].idx<<shift);
143 }
144 
145 
146 /*
147  check if a frame type should be included. A frame is included if
148  either there are no frame type flags on a parameter or if at least
149  one of the flags has been set by set_frame_type_flags()
150  */
151 bool AP_Param::check_frame_type(uint16_t flags)
152 {
153  uint16_t frame_flags = flags >> AP_PARAM_FRAME_TYPE_SHIFT;
154  if (frame_flags == 0) {
155  return true;
156  }
157  return (frame_flags & _frame_type_flags) != 0;
158 }
159 
160 // validate a group info table
161 bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
162  uint16_t * total_size,
163  uint8_t group_shift,
164  uint8_t prefix_length)
165 {
166  uint8_t type;
167  uint64_t used_mask = 0;
168  for (uint8_t i=0;
169  (type=group_info[i].type) != AP_PARAM_NONE;
170  i++) {
171  uint8_t idx = group_info[i].idx;
172  if (idx >= (1<<_group_level_shift)) {
173  Debug("idx too large (%u) in %s", idx, group_info[i].name);
174  return false;
175  }
176  if (group_shift != 0 && idx == 0) {
177  // great idx 0 as 63 for duplicates. See group_id()
178  idx = 63;
179  }
180  if (used_mask & (1ULL<<idx)) {
181  Debug("Duplicate group idx %u for %s", idx, group_info[i].name);
182  return false;
183  }
184  used_mask |= (1ULL<<idx);
185  if (type == AP_PARAM_GROUP) {
186  // a nested group
187  if (group_shift + _group_level_shift >= _group_bits) {
188  Debug("double group nesting in %s", group_info[i].name);
189  return false;
190  }
191  const struct GroupInfo *ginfo = get_group_info(group_info[i]);
192  if (ginfo == nullptr) {
193  continue;
194  }
195  if (!check_group_info(ginfo, total_size, group_shift + _group_level_shift, prefix_length + strlen(group_info[i].name))) {
196  return false;
197  }
198  continue;
199  }
200  uint8_t size = type_size((enum ap_var_type)type);
201  if (size == 0) {
202  Debug("invalid type in %s", group_info[i].name);
203  return false;
204  }
205  if (prefix_length + strlen(group_info[i].name) > 16) {
206  Debug("suffix is too long in %s", group_info[i].name);
207  return false;
208  }
209  (*total_size) += size + sizeof(struct Param_header);
210  }
211  return true;
212 }
213 
214 // check for duplicate key values
215 bool AP_Param::duplicate_key(uint16_t vindex, uint16_t key)
216 {
217  for (uint16_t i=vindex+1; i<_num_vars; i++) {
218  uint16_t key2 = _var_info[i].key;
219  if (key2 == key) {
220  // no duplicate keys allowed
221  return true;
222  }
223  }
224  return false;
225 }
226 
227 /*
228  get group_info pointer for a group
229  */
230 const struct AP_Param::GroupInfo *AP_Param::get_group_info(const struct GroupInfo &ginfo)
231 {
232  if (ginfo.flags & AP_PARAM_FLAG_INFO_POINTER) {
233  return *ginfo.group_info_ptr;
234  }
235  return ginfo.group_info;
236 }
237 
238 /*
239  get group_info pointer for a group
240  */
241 const struct AP_Param::GroupInfo *AP_Param::get_group_info(const struct Info &info)
242 {
243  if (info.flags & AP_PARAM_FLAG_INFO_POINTER) {
244  return *info.group_info_ptr;
245  }
246  return info.group_info;
247 }
248 
249 // validate the _var_info[] table
251 {
252  uint16_t total_size = sizeof(struct EEPROM_header);
253 
254  for (uint16_t i=0; i<_num_vars; i++) {
255  uint8_t type = _var_info[i].type;
256  uint16_t key = _var_info[i].key;
257  if (type == AP_PARAM_GROUP) {
258  if (i == 0) {
259  // first element can't be a group, for first() call
260  return false;
261  }
262  const struct GroupInfo *group_info = get_group_info(_var_info[i]);
263  if (group_info == nullptr) {
264  continue;
265  }
266  if (!check_group_info(group_info, &total_size, 0, strlen(_var_info[i].name))) {
267  return false;
268  }
269  } else {
270  uint8_t size = type_size((enum ap_var_type)type);
271  if (size == 0) {
272  // not a valid type - the top level list can't contain
273  // AP_PARAM_NONE
274  return false;
275  }
276  total_size += size + sizeof(struct Param_header);
277  }
278  if (duplicate_key(i, key)) {
279  return false;
280  }
281  if (type != AP_PARAM_GROUP && (_var_info[i].flags & AP_PARAM_FLAG_POINTER)) {
282  // only groups can be pointers
283  return false;
284  }
285  }
286 
287  // we no longer check if total_size is larger than _eeprom_size,
288  // as we allow for more variables than could fit, relying on not
289  // saving default values
290 
291  return true;
292 }
293 
294 
295 // setup the _var_info[] table
296 bool AP_Param::setup(void)
297 {
298  struct EEPROM_header hdr;
299 
300  // check the header
301  _storage.read_block(&hdr, 0, sizeof(hdr));
302  if (hdr.magic[0] != k_EEPROM_magic0 ||
303  hdr.magic[1] != k_EEPROM_magic1 ||
304  hdr.revision != k_EEPROM_revision) {
305  // header doesn't match. We can't recover any variables. Wipe
306  // the header and setup the sentinal directly after the header
307  Debug("bad header in setup - erasing");
308  erase_all();
309  }
310 
311  return true;
312 }
313 
314 // check if AP_Param has been initialised
316 {
317  return _var_info != nullptr;
318 }
319 
320 /*
321  adjust offset of a group element for nested groups and group pointers
322 
323  The new_offset variable is relative to the vindex base. This makes
324  dealing with pointer groups tricky
325  */
326 bool AP_Param::adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset)
327 {
328  if (group_info.flags & AP_PARAM_FLAG_NESTED_OFFSET) {
329  new_offset += group_info.offset;
330  return true;
331  }
332  if (group_info.flags & AP_PARAM_FLAG_POINTER) {
333  // group_info.offset refers to a pointer
334  ptrdiff_t base;
335  if (!get_base(_var_info[vindex], base)) {
336  // the object is not allocated yet
337  return false;
338  }
339  void **p = (void **)(base + new_offset + group_info.offset);
340  if (*p == nullptr) {
341  // the object is not allocated yet
342  return false;
343  }
344  // calculate offset that is needed to take base object and adjust for this object
345  new_offset = ((ptrdiff_t)*p) - base;
346  }
347  return true;
348 }
349 
350 /*
351  get the base pointer for a variable, accounting for AP_PARAM_FLAG_POINTER
352  */
353 bool AP_Param::get_base(const struct Info &info, ptrdiff_t &base)
354 {
355  if (info.flags & AP_PARAM_FLAG_POINTER) {
356  base = *(ptrdiff_t *)info.ptr;
357  return (base != (ptrdiff_t)0);
358  }
359  base = (ptrdiff_t)info.ptr;
360  return true;
361 }
362 
363 
364 // find the info structure given a header and a group_info table
365 // return the Info structure and a pointer to the variables storage
367  uint16_t vindex,
368  const struct GroupInfo *group_info,
369  uint32_t group_base,
370  uint8_t group_shift,
371  ptrdiff_t group_offset)
372 {
373  uint8_t type;
374  for (uint8_t i=0;
375  (type=group_info[i].type) != AP_PARAM_NONE;
376  i++) {
377  if (type == AP_PARAM_GROUP) {
378  // a nested group
379  if (group_shift + _group_level_shift >= _group_bits) {
380  // too deeply nested - this should have been caught by
381  // setup() !
382  return nullptr;
383  }
384  const struct GroupInfo *ginfo = get_group_info(group_info[i]);
385  if (ginfo == nullptr) {
386  continue;
387  }
388  ptrdiff_t new_offset = group_offset;
389 
390  if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
391  continue;
392  }
393 
394  const struct AP_Param::Info *ret = find_by_header_group(phdr, ptr, vindex, ginfo,
395  group_id(group_info, group_base, i, group_shift),
396  group_shift + _group_level_shift, new_offset);
397  if (ret != nullptr) {
398  return ret;
399  }
400  continue;
401  }
402  if (group_id(group_info, group_base, i, group_shift) == phdr.group_element && type == phdr.type) {
403  // found a group element
404  ptrdiff_t base;
405  if (!get_base(_var_info[vindex], base)) {
406  continue;
407  }
408  *ptr = (void*)(base + group_info[i].offset + group_offset);
409  return &_var_info[vindex];
410  }
411  }
412  return nullptr;
413 }
414 
415 // find the info structure given a header
416 // return the Info structure and a pointer to the variables storage
417 const struct AP_Param::Info *AP_Param::find_by_header(struct Param_header phdr, void **ptr)
418 {
419  // loop over all named variables
420  for (uint16_t i=0; i<_num_vars; i++) {
421  uint8_t type = _var_info[i].type;
422  uint16_t key = _var_info[i].key;
423  if (key != get_key(phdr)) {
424  // not the right key
425  continue;
426  }
427  if (type == AP_PARAM_GROUP) {
428  const struct GroupInfo *group_info = get_group_info(_var_info[i]);
429  if (group_info == nullptr) {
430  continue;
431  }
432  return find_by_header_group(phdr, ptr, i, group_info, 0, 0, 0);
433  }
434  if (type == phdr.type) {
435  // found it
436  ptrdiff_t base;
437  if (!get_base(_var_info[i], base)) {
438  return nullptr;
439  }
440  *ptr = (void*)base;
441  return &_var_info[i];
442  }
443  }
444  return nullptr;
445 }
446 
447 // find the info structure for a variable in a group
449  uint16_t vindex,
450  uint32_t group_base,
451  uint8_t group_shift,
452  ptrdiff_t group_offset,
453  uint32_t * group_element,
454  const struct GroupInfo * &group_ret,
455  struct GroupNesting &group_nesting,
456  uint8_t * idx) const
457 {
458  ptrdiff_t base;
459  if (!get_base(_var_info[vindex], base)) {
460  return nullptr;
461  }
462  uint8_t type;
463  for (uint8_t i=0;
464  (type=group_info[i].type) != AP_PARAM_NONE;
465  i++) {
466  ptrdiff_t ofs = group_info[i].offset + group_offset;
467  if (type == AP_PARAM_GROUP) {
468  const struct GroupInfo *ginfo = get_group_info(group_info[i]);
469  if (ginfo == nullptr) {
470  continue;
471  }
472  // a nested group
473  if (group_shift + _group_level_shift >= _group_bits) {
474  // too deeply nested - this should have been caught by
475  // setup() !
476  return nullptr;
477  }
478  const struct AP_Param::Info *info;
479  ptrdiff_t new_offset = group_offset;
480  if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
481  continue;
482  }
483  if (group_nesting.level >= group_nesting.numlevels) {
484  return nullptr;
485  }
486  group_nesting.group_ret[group_nesting.level++] = &group_info[i];
487  info = find_var_info_group(ginfo, vindex,
488  group_id(group_info, group_base, i, group_shift),
489  group_shift + _group_level_shift,
490  new_offset,
491  group_element,
492  group_ret,
493  group_nesting,
494  idx);
495  if (info != nullptr) {
496  return info;
497  }
498  group_nesting.level--;
499  } else if ((ptrdiff_t) this == base + ofs) {
500  *group_element = group_id(group_info, group_base, i, group_shift);
501  group_ret = &group_info[i];
502  *idx = 0;
503  return &_var_info[vindex];
504  } else if (type == AP_PARAM_VECTOR3F &&
505  (base+ofs+(ptrdiff_t)sizeof(float) == (ptrdiff_t) this ||
506  base+ofs+2*(ptrdiff_t)sizeof(float) == (ptrdiff_t) this)) {
507  // we are inside a Vector3f. We need to work out which
508  // element of the vector the current object refers to.
509  *idx = (((ptrdiff_t) this) - (base+ofs))/sizeof(float);
510  *group_element = group_id(group_info, group_base, i, group_shift);
511  group_ret = &group_info[i];
512  return &_var_info[vindex];
513  }
514  }
515  return nullptr;
516 }
517 
518 // find the info structure for a variable
519 const struct AP_Param::Info *AP_Param::find_var_info(uint32_t * group_element,
520  const struct GroupInfo * &group_ret,
521  struct GroupNesting &group_nesting,
522  uint8_t * idx) const
523 {
524  group_ret = nullptr;
525 
526  for (uint16_t i=0; i<_num_vars; i++) {
527  uint8_t type = _var_info[i].type;
528  ptrdiff_t base;
529  if (!get_base(_var_info[i], base)) {
530  continue;
531  }
532  if (type == AP_PARAM_GROUP) {
533  const struct GroupInfo *group_info = get_group_info(_var_info[i]);
534  if (group_info == nullptr) {
535  continue;
536  }
537  const struct AP_Param::Info *info;
538  info = find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx);
539  if (info != nullptr) {
540  return info;
541  }
542  } else if (base == (ptrdiff_t) this) {
543  *group_element = 0;
544  *idx = 0;
545  return &_var_info[i];
546  } else if (type == AP_PARAM_VECTOR3F &&
547  (base+(ptrdiff_t)sizeof(float) == (ptrdiff_t) this ||
548  base+2*(ptrdiff_t)sizeof(float) == (ptrdiff_t) this)) {
549  // we are inside a Vector3f. Work out which element we are
550  // referring to.
551  *idx = (((ptrdiff_t) this) - base)/sizeof(float);
552  *group_element = 0;
553  return &_var_info[i];
554  }
555  }
556  return nullptr;
557 }
558 
559 
560 // find the info structure for a variable
562  uint32_t * group_element,
563  const struct GroupInfo * &group_ret,
564  struct GroupNesting &group_nesting,
565  uint8_t * idx) const
566 {
567  uint16_t i = token.key;
568  uint8_t type = _var_info[i].type;
569  ptrdiff_t base;
570  if (!get_base(_var_info[i], base)) {
571  return nullptr;
572  }
573  group_ret = nullptr;
574 
575  if (type == AP_PARAM_GROUP) {
576  const struct GroupInfo *group_info = get_group_info(_var_info[i]);
577  if (group_info == nullptr) {
578  return nullptr;
579  }
580  const struct AP_Param::Info *info;
581  info = find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx);
582  if (info != nullptr) {
583  return info;
584  }
585  } else if (base == (ptrdiff_t) this) {
586  *group_element = 0;
587  *idx = 0;
588  return &_var_info[i];
589  } else if (type == AP_PARAM_VECTOR3F &&
590  (base+(ptrdiff_t)sizeof(float) == (ptrdiff_t) this ||
591  base+2*(ptrdiff_t)sizeof(float) == (ptrdiff_t) this)) {
592  // we are inside a Vector3f. Work out which element we are
593  // referring to.
594  *idx = (((ptrdiff_t) this) - base)/sizeof(float);
595  *group_element = 0;
596  return &_var_info[i];
597  }
598  return nullptr;
599 }
600 
601 // return the storage size for a AP_PARAM_* type
603 {
604  switch (type) {
605  case AP_PARAM_NONE:
606  case AP_PARAM_GROUP:
607  return 0;
608  case AP_PARAM_INT8:
609  return 1;
610  case AP_PARAM_INT16:
611  return 2;
612  case AP_PARAM_INT32:
613  return 4;
614  case AP_PARAM_FLOAT:
615  return 4;
616  case AP_PARAM_VECTOR3F:
617  return 3*4;
618  }
619  Debug("unknown type %u\n", type);
620  return 0;
621 }
622 
623 /*
624  extract 9 bit key from Param_header
625  */
626 uint16_t AP_Param::get_key(const Param_header &phdr)
627 {
628  return ((uint16_t)phdr.key_high)<<8 | phdr.key_low;
629 }
630 
631 /*
632  set 9 bit key in Param_header
633  */
634 void AP_Param::set_key(Param_header &phdr, uint16_t key)
635 {
636  phdr.key_low = key & 0xFF;
637  phdr.key_high = key >> 8;
638 }
639 
640 /*
641  return true if a header is the end of eeprom sentinal
642  */
644 {
645  // note that this is an ||, not an &&, as this makes us more
646  // robust to power off while adding a variable to EEPROM
647  if (phdr.type == _sentinal_type ||
648  get_key(phdr) == _sentinal_key ||
649  phdr.group_element == _sentinal_group) {
650  return true;
651  }
652  // also check for 0xFFFFFFFF and 0x00000000, which are the fill
653  // values for storage. These can appear if power off occurs while
654  // writing data
655  uint32_t v = *(uint32_t *)&phdr;
656  if (v == 0 || v == 0xFFFFFFFF) {
657  return true;
658  }
659  return false;
660 }
661 
662 // scan the EEPROM looking for a given variable by header content
663 // return true if found, along with the offset in the EEPROM where
664 // the variable is stored
665 // if not found return the offset of the sentinal
666 // if the sentinal isn't found either, the offset is set to 0xFFFF
667 bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs)
668 {
669  struct Param_header phdr;
670  uint16_t ofs = sizeof(AP_Param::EEPROM_header);
671  while (ofs < _storage.size()) {
672  _storage.read_block(&phdr, ofs, sizeof(phdr));
673  if (phdr.type == target->type &&
674  get_key(phdr) == get_key(*target) &&
675  phdr.group_element == target->group_element) {
676  // found it
677  *pofs = ofs;
678  return true;
679  }
680  if (is_sentinal(phdr)) {
681  // we've reached the sentinal
682  *pofs = ofs;
683  return false;
684  }
685  ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
686  }
687  *pofs = 0xffff;
688  Debug("scan past end of eeprom");
689  return false;
690 }
691 
698 void AP_Param::add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx) const
699 {
700  const size_t len = strnlen(buffer, buffer_size);
701  if (len + 2 <= buffer_size) {
702  buffer[len] = '_';
703  buffer[len + 1] = static_cast<char>('X' + idx);
704  if (len + 3 <= buffer_size) {
705  buffer[len + 2] = 0;
706  }
707  }
708 }
709 
710 // Copy the variable's whole name to the supplied buffer.
711 //
712 // If the variable is a group member, prepend the group name.
713 //
714 void AP_Param::copy_name_token(const ParamToken &token, char *buffer, size_t buffer_size, bool force_scalar) const
715 {
716  uint32_t group_element;
717  const struct GroupInfo *ginfo;
718  struct GroupNesting group_nesting {};
719  uint8_t idx;
720  const struct AP_Param::Info *info = find_var_info_token(token, &group_element, ginfo, group_nesting, &idx);
721  if (info == nullptr) {
722  *buffer = 0;
723  Debug("no info found");
724  return;
725  }
726  copy_name_info(info, ginfo, group_nesting, idx, buffer, buffer_size, force_scalar);
727 }
728 
729 void AP_Param::copy_name_info(const struct AP_Param::Info *info,
730  const struct GroupInfo *ginfo,
731  const struct GroupNesting &group_nesting,
732  uint8_t idx, char *buffer, size_t buffer_size, bool force_scalar) const
733 {
734  strncpy(buffer, info->name, buffer_size);
735  for (uint8_t i=0; i<group_nesting.level; i++) {
736  uint8_t len = strnlen(buffer, buffer_size);
737  if (len < buffer_size) {
738  strncpy(&buffer[len], group_nesting.group_ret[i]->name, buffer_size-len);
739  }
740  }
741  if (ginfo != nullptr) {
742  uint8_t len = strnlen(buffer, buffer_size);
743  if (len < buffer_size) {
744  strncpy(&buffer[len], ginfo->name, buffer_size-len);
745  }
746  if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == ginfo->type) {
747  // the caller wants a specific element in a Vector3f
748  add_vector3f_suffix(buffer, buffer_size, idx);
749  }
750  } else if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == info->type) {
751  add_vector3f_suffix(buffer, buffer_size, idx);
752  }
753 }
754 
755 // Find a variable by name in a group
756 AP_Param *
757 AP_Param::find_group(const char *name, uint16_t vindex, ptrdiff_t group_offset,
758  const struct GroupInfo *group_info, enum ap_var_type *ptype)
759 {
760  uint8_t type;
761  for (uint8_t i=0;
762  (type=group_info[i].type) != AP_PARAM_NONE;
763  i++) {
764  if (type == AP_PARAM_GROUP) {
765  if (strncasecmp(name, group_info[i].name, strlen(group_info[i].name)) != 0) {
766  continue;
767  }
768  const struct GroupInfo *ginfo = get_group_info(group_info[i]);
769  if (ginfo == nullptr) {
770  continue;
771  }
772  ptrdiff_t new_offset = group_offset;
773 
774  if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
775  continue;
776  }
777 
778  AP_Param *ap = find_group(name+strlen(group_info[i].name), vindex, new_offset, ginfo, ptype);
779  if (ap != nullptr) {
780  return ap;
781  }
782  } else if (strcasecmp(name, group_info[i].name) == 0) {
783  ptrdiff_t base;
784  if (!get_base(_var_info[vindex], base)) {
785  continue;
786  }
787  *ptype = (enum ap_var_type)type;
788  return (AP_Param *)(base + group_info[i].offset + group_offset);
789  } else if (type == AP_PARAM_VECTOR3F) {
790  // special case for finding Vector3f elements
791  uint8_t suffix_len = strnlen(group_info[i].name, AP_MAX_NAME_SIZE);
792  if (strncmp(name, group_info[i].name, suffix_len) == 0 &&
793  name[suffix_len] == '_' &&
794  (name[suffix_len+1] == 'X' ||
795  name[suffix_len+1] == 'Y' ||
796  name[suffix_len+1] == 'Z')) {
797  ptrdiff_t base;
798  if (!get_base(_var_info[vindex], base)) {
799  continue;
800  }
801  AP_Float *v = (AP_Float *)(base + group_info[i].offset + group_offset);
802  *ptype = AP_PARAM_FLOAT;
803  switch (name[suffix_len+1]) {
804  case 'X':
805  return (AP_Float *)&v[0];
806  case 'Y':
807  return (AP_Float *)&v[1];
808  case 'Z':
809  return (AP_Float *)&v[2];
810  }
811  }
812  }
813  }
814  return nullptr;
815 }
816 
817 
818 // Find a variable by name.
819 //
820 AP_Param *
821 AP_Param::find(const char *name, enum ap_var_type *ptype)
822 {
823  for (uint16_t i=0; i<_num_vars; i++) {
824  uint8_t type = _var_info[i].type;
825  if (type == AP_PARAM_GROUP) {
826  uint8_t len = strnlen(_var_info[i].name, AP_MAX_NAME_SIZE);
827  if (strncmp(name, _var_info[i].name, len) != 0) {
828  continue;
829  }
830  const struct GroupInfo *group_info = get_group_info(_var_info[i]);
831  if (group_info == nullptr) {
832  continue;
833  }
834  AP_Param *ap = find_group(name + len, i, 0, group_info, ptype);
835  if (ap != nullptr) {
836  return ap;
837  }
838  // we continue looking as we want to allow top level
839  // parameter to have the same prefix name as group
840  // parameters, for example CAM_P_G
841  } else if (strcasecmp(name, _var_info[i].name) == 0) {
842  *ptype = (enum ap_var_type)type;
843  ptrdiff_t base;
844  if (!get_base(_var_info[i], base)) {
845  return nullptr;
846  }
847  return (AP_Param *)base;
848  }
849  }
850  return nullptr;
851 }
852 
853 // Find a variable by index. Note that this is quite slow.
854 //
855 AP_Param *
856 AP_Param::find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)
857 {
858  AP_Param *ap;
859  uint16_t count=0;
860  for (ap=AP_Param::first(token, ptype);
861  ap && count < idx;
862  ap=AP_Param::next_scalar(token, ptype)) {
863  count++;
864  }
865  return ap;
866 }
867 
868 
869 /*
870  Find a variable by pointer, returning key. This is used for loading pointer variables
871 */
872 bool AP_Param::find_key_by_pointer_group(const void *ptr, uint16_t vindex,
873  const struct GroupInfo *group_info,
874  ptrdiff_t offset, uint16_t &key)
875 {
876  for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
877  if (group_info[i].type != AP_PARAM_GROUP) {
878  continue;
879  }
880  ptrdiff_t base;
881  if (!get_base(_var_info[vindex], base)) {
882  continue;
883  }
884  if (group_info[i].flags & AP_PARAM_FLAG_POINTER) {
885  if (ptr == *(void **)(base+group_info[i].offset+offset)) {
886  key = _var_info[vindex].key;
887  return true;
888  }
889  } else if (ptr == (void *)(base+group_info[i].offset+offset)) {
890  key = _var_info[vindex].key;
891  return true;
892  }
893  ptrdiff_t new_offset = offset;
894  if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
895  continue;
896  }
897  const struct GroupInfo *ginfo = get_group_info(group_info[i]);
898  if (ginfo == nullptr) {
899  continue;
900  }
901  if (find_key_by_pointer_group(ptr, vindex, ginfo, new_offset, key)) {
902  return true;
903  }
904  }
905  return false;
906 }
907 
908 
909 /*
910  Find a variable by pointer, returning key. This is used for loading pointer variables
911 */
912 bool AP_Param::find_key_by_pointer(const void *ptr, uint16_t &key)
913 {
914  for (uint16_t i=0; i<_num_vars; i++) {
915  if (_var_info[i].type != AP_PARAM_GROUP) {
916  continue;
917  }
918  if ((_var_info[i].flags & AP_PARAM_FLAG_POINTER) &&
919  ptr == *(void **)_var_info[i].ptr) {
920  key = _var_info[i].key;
921  return true;
922  }
923  ptrdiff_t offset = 0;
924  const struct GroupInfo *ginfo = get_group_info(_var_info[i]);
925  if (ginfo == nullptr) {
926  continue;
927  }
928  if (find_key_by_pointer_group(ptr, i, ginfo, offset, key)) {
929  return true;
930  }
931  }
932  return false;
933 }
934 
935 
936 // Find a object by name.
937 //
938 AP_Param *
940 {
941  for (uint16_t i=0; i<_num_vars; i++) {
942  if (strcasecmp(name, _var_info[i].name) == 0) {
943  ptrdiff_t base;
944  if (!get_base(_var_info[i], base)) {
945  return nullptr;
946  }
947  return (AP_Param *)base;
948  }
949  }
950  return nullptr;
951 }
952 
953 // notify GCS of current value of parameter
954 void AP_Param::notify() const {
955  uint32_t group_element = 0;
956  const struct GroupInfo *ginfo;
957  struct GroupNesting group_nesting {};
958  uint8_t idx;
959 
960  const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
961  if (info == nullptr) {
962  // this is probably very bad
963  return;
964  }
965 
966  char name[AP_MAX_NAME_SIZE+1];
967  copy_name_info(info, ginfo, group_nesting, idx, name, sizeof(name), true);
968 
969  uint32_t param_header_type;
970  if (ginfo != nullptr) {
971  param_header_type = ginfo->type;
972  } else {
973  param_header_type = info->type;
974  }
975 
976  send_parameter(name, (enum ap_var_type)param_header_type, idx);
977 }
978 
979 
980 // Save the variable to EEPROM, if supported
981 //
982 bool AP_Param::save(bool force_save)
983 {
984  uint32_t group_element = 0;
985  const struct GroupInfo *ginfo;
986  struct GroupNesting group_nesting {};
987  uint8_t idx;
988  const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
989  const AP_Param *ap;
990 
991  if (info == nullptr) {
992  // we don't have any info on how to store it
993  return false;
994  }
995 
996  struct Param_header phdr;
997 
998  // create the header we will use to store the variable
999  if (ginfo != nullptr) {
1000  phdr.type = ginfo->type;
1001  } else {
1002  phdr.type = info->type;
1003  }
1004  set_key(phdr, info->key);
1006 
1007  ap = this;
1008  if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) {
1009  // only vector3f can have non-zero idx for now
1010  return false;
1011  }
1012  if (idx != 0) {
1013  ap = (const AP_Param *)((ptrdiff_t)ap) - (idx*sizeof(float));
1014  }
1015 
1016  if (phdr.type == AP_PARAM_INT8 && ginfo != nullptr && (ginfo->flags & AP_PARAM_FLAG_ENABLE)) {
1017  // clear cached parameter count
1018  _parameter_count = 0;
1019  }
1020 
1021  char name[AP_MAX_NAME_SIZE+1];
1022  copy_name_info(info, ginfo, group_nesting, idx, name, sizeof(name), true);
1023 
1024  // scan EEPROM to find the right location
1025  uint16_t ofs;
1026  if (scan(&phdr, &ofs)) {
1027  // found an existing copy of the variable
1028  eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
1029  send_parameter(name, (enum ap_var_type)phdr.type, idx);
1030  return true;
1031  }
1032  if (ofs == (uint16_t) ~0) {
1033  return false;
1034  }
1035 
1036  // if the value is the default value then don't save
1037  if (phdr.type <= AP_PARAM_FLOAT) {
1038  float v1 = cast_to_float((enum ap_var_type)phdr.type);
1039  float v2;
1040  if (ginfo != nullptr) {
1041  v2 = get_default_value(this, &ginfo->def_value);
1042  } else {
1043  v2 = get_default_value(this, &info->def_value);
1044  }
1045  if (is_equal(v1,v2) && !force_save) {
1046  gcs().send_parameter_value(name, (enum ap_var_type)info->type, v2);
1047  return true;
1048  }
1049  if (!force_save &&
1050  (phdr.type != AP_PARAM_INT32 &&
1051  (fabsf(v1-v2) < 0.0001f*fabsf(v1)))) {
1052  // for other than 32 bit integers, we accept values within
1053  // 0.01 percent of the current value as being the same
1054  gcs().send_parameter_value(name, (enum ap_var_type)info->type, v2);
1055  return true;
1056  }
1057  }
1058 
1059  if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _storage.size()) {
1060  // we are out of room for saving variables
1061  hal.console->printf("EEPROM full\n");
1062  return false;
1063  }
1064 
1065  // write a new sentinal, then the data, then the header
1066  write_sentinal(ofs + sizeof(phdr) + type_size((enum ap_var_type)phdr.type));
1067  eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
1068  eeprom_write_check(&phdr, ofs, sizeof(phdr));
1069 
1070  send_parameter(name, (enum ap_var_type)phdr.type, idx);
1071  return true;
1072 }
1073 
1074 // Load the variable from EEPROM, if supported
1075 //
1076 bool AP_Param::load(void)
1077 {
1078  uint32_t group_element = 0;
1079  const struct GroupInfo *ginfo;
1080  struct GroupNesting group_nesting {};
1081  uint8_t idx;
1082  const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
1083  if (info == nullptr) {
1084  // we don't have any info on how to load it
1085  return false;
1086  }
1087 
1088  struct Param_header phdr;
1089 
1090  // create the header we will use to match the variable
1091  if (ginfo != nullptr) {
1092  phdr.type = ginfo->type;
1093  } else {
1094  phdr.type = info->type;
1095  }
1096  set_key(phdr, info->key);
1098 
1099  // scan EEPROM to find the right location
1100  uint16_t ofs;
1101  if (!scan(&phdr, &ofs)) {
1102  // if the value isn't stored in EEPROM then set the default value
1103  ptrdiff_t base;
1104  if (!get_base(*info, base)) {
1105  return false;
1106  }
1107 
1108  if (ginfo != nullptr) {
1109  // add in nested group offset
1110  ptrdiff_t group_offset = 0;
1111  for (uint8_t i=0; i<group_nesting.level; i++) {
1112  group_offset += group_nesting.group_ret[i]->offset;
1113  }
1114  set_value((enum ap_var_type)phdr.type, (void*)(base + ginfo->offset + group_offset),
1115  get_default_value(this, &ginfo->def_value));
1116  } else {
1117  set_value((enum ap_var_type)phdr.type, (void*)base,
1118  get_default_value(this, &info->def_value));
1119  }
1120  return false;
1121  }
1122 
1123  if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) {
1124  // only vector3f can have non-zero idx for now
1125  return false;
1126  }
1127 
1128  AP_Param *ap;
1129  ap = this;
1130  if (idx != 0) {
1131  ap = (AP_Param *)((ptrdiff_t)ap) - (idx*sizeof(float));
1132  }
1133 
1134  // found it
1135  _storage.read_block(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
1136  return true;
1137 }
1138 
1140 {
1141  uint32_t group_element = 0;
1142  const struct GroupInfo *ginfo;
1143  struct GroupNesting group_nesting {};
1144  uint8_t idx;
1145  const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
1146  if (info == nullptr) {
1147  // we don't have any info on how to load it
1148  return false;
1149  }
1150 
1151  struct Param_header phdr;
1152 
1153  // create the header we will use to match the variable
1154  if (ginfo != nullptr) {
1155  phdr.type = ginfo->type;
1156  } else {
1157  phdr.type = info->type;
1158  }
1159  set_key(phdr, info->key);
1161 
1162  // scan EEPROM to find the right location
1163  uint16_t ofs;
1164 
1165  // only vector3f can have non-zero idx for now
1166  return scan(&phdr, &ofs) && (phdr.type == AP_PARAM_VECTOR3F || idx == 0);
1167 }
1168 
1170 {
1171  uint32_t group_element = 0;
1172  const struct GroupInfo *ginfo;
1173  struct GroupNesting group_nesting {};
1174  uint8_t idx;
1175  const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
1176  if (info == nullptr) {
1177  // we don't have any info on how to load it
1178  return false;
1179  }
1180 
1181  for (uint16_t i=0; i<num_param_overrides; i++) {
1182  if (this == param_overrides[i].object_ptr) {
1183  return true;
1184  }
1185  }
1186 
1187  return false;
1188 }
1189 
1190 // set a AP_Param variable to a specified value
1192 {
1193  switch (type) {
1194  case AP_PARAM_INT8:
1195  ((AP_Int8 *)ptr)->set(value);
1196  break;
1197  case AP_PARAM_INT16:
1198  ((AP_Int16 *)ptr)->set(value);
1199  break;
1200  case AP_PARAM_INT32:
1201  ((AP_Int32 *)ptr)->set(value);
1202  break;
1203  case AP_PARAM_FLOAT:
1204  ((AP_Float *)ptr)->set(value);
1205  break;
1206  default:
1207  break;
1208  }
1209 }
1210 
1211 // load default values for scalars in a group. This does not recurse
1212 // into other objects. This is a static function that should be called
1213 // in the objects constructor
1214 void AP_Param::setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
1215 {
1216  ptrdiff_t base = (ptrdiff_t)object_pointer;
1217  uint8_t type;
1218  for (uint8_t i=0;
1219  (type=group_info[i].type) != AP_PARAM_NONE;
1220  i++) {
1221  if (type <= AP_PARAM_FLOAT) {
1222  void *ptr = (void *)(base + group_info[i].offset);
1223  set_value((enum ap_var_type)type, ptr,
1224  get_default_value((const AP_Param *)ptr, &group_info[i].def_value));
1225  }
1226  }
1227 }
1228 
1229 // set a value directly in an object. This should only be used by
1230 // example code, not by mainline vehicle code
1231 bool AP_Param::set_object_value(const void *object_pointer,
1232  const struct GroupInfo *group_info,
1233  const char *name, float value)
1234 {
1235  ptrdiff_t base = (ptrdiff_t)object_pointer;
1236  uint8_t type;
1237  bool found = false;
1238  for (uint8_t i=0;
1239  (type=group_info[i].type) != AP_PARAM_NONE;
1240  i++) {
1241  if (strcmp(name, group_info[i].name) == 0 && type <= AP_PARAM_FLOAT) {
1242  void *ptr = (void *)(base + group_info[i].offset);
1243  set_value((enum ap_var_type)type, ptr, value);
1244  // return true here ?
1245  found = true;
1246  }
1247  }
1248  return found;
1249 }
1250 
1251 
1252 // load default values for all scalars in a sketch. This does not
1253 // recurse into sub-objects
1255 {
1256  setup();
1257  for (uint16_t i=0; i<_num_vars; i++) {
1258  uint8_t type = _var_info[i].type;
1259  if (type <= AP_PARAM_FLOAT) {
1260  ptrdiff_t base;
1261  if (get_base(_var_info[i], base)) {
1262  set_value((enum ap_var_type)type, (void*)base,
1263  get_default_value((const AP_Param *)base, &_var_info[i].def_value));
1264  }
1265  }
1266  }
1267 }
1268 
1269 
1270 // Load all variables from EEPROM
1271 //
1272 bool AP_Param::load_all(bool check_defaults_file)
1273 {
1274  struct Param_header phdr;
1275  uint16_t ofs = sizeof(AP_Param::EEPROM_header);
1276 
1277  reload_defaults_file(check_defaults_file);
1278 
1279  while (ofs < _storage.size()) {
1280  _storage.read_block(&phdr, ofs, sizeof(phdr));
1281  // note that this is an || not an && for robustness
1282  // against power off while adding a variable
1283  if (is_sentinal(phdr)) {
1284  // we've reached the sentinal
1285  return true;
1286  }
1287 
1288  const struct AP_Param::Info *info;
1289  void *ptr;
1290 
1291  info = find_by_header(phdr, &ptr);
1292  if (info != nullptr) {
1293  _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
1294  }
1295 
1296  ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
1297  }
1298 
1299  // we didn't find the sentinal
1300  Debug("no sentinal in load_all");
1301  return false;
1302 }
1303 
1304 /*
1305  reload from hal.util defaults file
1306  */
1307 void AP_Param::reload_defaults_file(bool panic_on_error)
1308 {
1309  if (param_defaults_data.length != 0) {
1311  return;
1312  }
1313 
1314 #if HAL_OS_POSIX_IO == 1
1315  /*
1316  if the HAL specifies a defaults parameter file then override
1317  defaults using that file
1318  */
1319  const char *default_file = hal.util->get_custom_defaults_file();
1320  if (default_file) {
1321  if (load_defaults_file(default_file, panic_on_error)) {
1322  printf("Loaded defaults from %s\n", default_file);
1323  } else {
1324  printf("Failed to load defaults from %s\n", default_file);
1325  }
1326  }
1327 #endif
1328 }
1329 
1330 
1331 /*
1332  Load all variables from EEPROM for a particular object. This is
1333  required for dynamically loaded objects
1334  */
1335 void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
1336 {
1337  struct Param_header phdr;
1338  uint16_t key;
1339 
1340  // reset cached param counter as we may be loading a dynamic var_info
1341  _parameter_count = 0;
1342 
1343  if (!find_key_by_pointer(object_pointer, key)) {
1344  hal.console->printf("ERROR: Unable to find param pointer\n");
1345  return;
1346  }
1347 
1348  for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
1349  if (group_info[i].type == AP_PARAM_GROUP) {
1350  ptrdiff_t new_offset = 0;
1351  if (!adjust_group_offset(key, group_info[i], new_offset)) {
1352  continue;
1353  }
1354  const struct GroupInfo *ginfo = get_group_info(group_info[i]);
1355  if (ginfo != nullptr) {
1356  load_object_from_eeprom((void *)(((ptrdiff_t)object_pointer)+new_offset), ginfo);
1357  }
1358  }
1359  uint16_t ofs = sizeof(AP_Param::EEPROM_header);
1360  while (ofs < _storage.size()) {
1361  _storage.read_block(&phdr, ofs, sizeof(phdr));
1362  // note that this is an || not an && for robustness
1363  // against power off while adding a variable
1364  if (is_sentinal(phdr)) {
1365  // we've reached the sentinal
1366  break;
1367  }
1368  if (get_key(phdr) == key) {
1369  const struct AP_Param::Info *info;
1370  void *ptr;
1371 
1372  info = find_by_header(phdr, &ptr);
1373  if (info != nullptr) {
1374  if ((ptrdiff_t)ptr == ((ptrdiff_t)object_pointer)+group_info[i].offset) {
1375  _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
1376  break;
1377  }
1378  }
1379  }
1380  ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
1381  }
1382  }
1383 }
1384 
1385 
1386 // return the first variable in _var_info
1388 {
1389  token->key = 0;
1390  token->group_element = 0;
1391  token->idx = 0;
1392  if (_num_vars == 0) {
1393  return nullptr;
1394  }
1395  if (ptype != nullptr) {
1396  *ptype = (enum ap_var_type)_var_info[0].type;
1397  }
1398  ptrdiff_t base;
1399  if (!get_base(_var_info[0], base)) {
1400  // should be impossible, first var needs to be non-pointer
1401  return nullptr;
1402  }
1403  return (AP_Param *)base;
1404 }
1405 
1408 AP_Param *AP_Param::next_group(uint16_t vindex, const struct GroupInfo *group_info,
1409  bool *found_current,
1410  uint32_t group_base,
1411  uint8_t group_shift,
1412  ptrdiff_t group_offset,
1413  ParamToken *token,
1414  enum ap_var_type *ptype)
1415 {
1416  enum ap_var_type type;
1417  for (uint8_t i=0;
1418  (type=(enum ap_var_type)group_info[i].type) != AP_PARAM_NONE;
1419  i++) {
1420  if (!check_frame_type(group_info[i].flags)) {
1421  continue;
1422  }
1423  if (type == AP_PARAM_GROUP) {
1424  // a nested group
1425  const struct GroupInfo *ginfo = get_group_info(group_info[i]);
1426  if (ginfo == nullptr) {
1427  continue;
1428  }
1429  AP_Param *ap;
1430  ptrdiff_t new_offset = group_offset;
1431 
1432  if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
1433  continue;
1434  }
1435 
1436  ap = next_group(vindex, ginfo, found_current, group_id(group_info, group_base, i, group_shift),
1437  group_shift + _group_level_shift, new_offset, token, ptype);
1438  if (ap != nullptr) {
1439  return ap;
1440  }
1441  } else {
1442  if (*found_current) {
1443  // got a new one
1444  token->key = vindex;
1445  token->group_element = group_id(group_info, group_base, i, group_shift);
1446  token->idx = 0;
1447  if (ptype != nullptr) {
1448  *ptype = type;
1449  }
1450  ptrdiff_t base;
1451  if (!get_base(_var_info[vindex], base)) {
1452  continue;
1453  }
1454  return (AP_Param*)(base + group_info[i].offset + group_offset);
1455  }
1456  if (group_id(group_info, group_base, i, group_shift) == token->group_element) {
1457  *found_current = true;
1458  if (type == AP_PARAM_VECTOR3F && token->idx < 3) {
1459  // return the next element of the vector as a
1460  // float
1461  token->idx++;
1462  if (ptype != nullptr) {
1463  *ptype = AP_PARAM_FLOAT;
1464  }
1465  ptrdiff_t base;
1466  if (!get_base(_var_info[vindex], base)) {
1467  continue;
1468  }
1469  ptrdiff_t ofs = base + group_info[i].offset + group_offset;
1470  ofs += sizeof(float)*(token->idx - 1u);
1471  return (AP_Param *)ofs;
1472  }
1473  }
1474  }
1475  }
1476  return nullptr;
1477 }
1478 
1482 {
1483  uint16_t i = token->key;
1484  bool found_current = false;
1485  if (i >= _num_vars) {
1486  // illegal token
1487  return nullptr;
1488  }
1489  enum ap_var_type type = (enum ap_var_type)_var_info[i].type;
1490 
1491  // allow Vector3f to be seen as 3 variables. First as a vector,
1492  // then as 3 separate floats
1493  if (type == AP_PARAM_VECTOR3F && token->idx < 3) {
1494  token->idx++;
1495  if (ptype != nullptr) {
1496  *ptype = AP_PARAM_FLOAT;
1497  }
1498  return (AP_Param *)(((token->idx - 1u)*sizeof(float))+(ptrdiff_t)_var_info[i].ptr);
1499  }
1500 
1501  if (type != AP_PARAM_GROUP) {
1502  i++;
1503  found_current = true;
1504  }
1505  for (; i<_num_vars; i++) {
1506  if (!check_frame_type(_var_info[i].flags)) {
1507  continue;
1508  }
1509  type = (enum ap_var_type)_var_info[i].type;
1510  if (type == AP_PARAM_GROUP) {
1511  const struct GroupInfo *group_info = get_group_info(_var_info[i]);
1512  if (group_info == nullptr) {
1513  continue;
1514  }
1515  AP_Param *ap = next_group(i, group_info, &found_current, 0, 0, 0, token, ptype);
1516  if (ap != nullptr) {
1517  return ap;
1518  }
1519  } else {
1520  // found the next one
1521  token->key = i;
1522  token->group_element = 0;
1523  token->idx = 0;
1524  if (ptype != nullptr) {
1525  *ptype = type;
1526  }
1527  return (AP_Param *)(_var_info[i].ptr);
1528  }
1529  }
1530  return nullptr;
1531 }
1532 
1536 {
1537  AP_Param *ap;
1538  enum ap_var_type type;
1539  while ((ap = next(token, &type)) != nullptr && type > AP_PARAM_FLOAT) ;
1540 
1541  if (ap != nullptr && type == AP_PARAM_INT8) {
1542  /*
1543  check if this is an enable variable. To do that we need to
1544  find the info structures for the variable
1545  */
1546  uint32_t group_element;
1547  const struct GroupInfo *ginfo;
1548  struct GroupNesting group_nesting {};
1549  uint8_t idx;
1550  const struct AP_Param::Info *info = ap->find_var_info_token(*token, &group_element,
1551  ginfo, group_nesting, &idx);
1552  if (info && ginfo &&
1553  (ginfo->flags & AP_PARAM_FLAG_ENABLE) &&
1554  !(ginfo->flags & AP_PARAM_FLAG_IGNORE_ENABLE) &&
1555  ((AP_Int8 *)ap)->get() == 0 &&
1557  /*
1558  this is a disabled parameter tree, include this
1559  parameter but not others below it. We need to keep
1560  looking until we go past the parameters in this object
1561  */
1562  ParamToken token2 = *token;
1563  enum ap_var_type type2;
1564  AP_Param *ap2;
1565  while ((ap2 = next(&token2, &type2)) != nullptr) {
1566  if (token2.key != token->key) {
1567  break;
1568  }
1569  if (group_nesting.level != 0 && (token->group_element & 0x3F) != (token2.group_element & 0x3F)) {
1570  break;
1571  }
1572  // update the returned token so the next() call goes from this point
1573  *token = token2;
1574  }
1575 
1576  }
1577  }
1578 
1579  if (ap != nullptr && ptype != nullptr) {
1580  *ptype = type;
1581  }
1582  return ap;
1583 }
1584 
1585 
1588 {
1589  switch (type) {
1590  case AP_PARAM_INT8:
1591  return ((AP_Int8 *)this)->cast_to_float();
1592  case AP_PARAM_INT16:
1593  return ((AP_Int16 *)this)->cast_to_float();
1594  case AP_PARAM_INT32:
1595  return ((AP_Int32 *)this)->cast_to_float();
1596  case AP_PARAM_FLOAT:
1597  return ((AP_Float *)this)->cast_to_float();
1598  default:
1599  return NAN;
1600  }
1601 }
1602 
1603 /*
1604  find an old parameter and return it.
1605  */
1607 {
1608  // find the old value in EEPROM.
1609  uint16_t pofs;
1610  AP_Param::Param_header header;
1611  header.type = info->type;
1612  set_key(header, info->old_key);
1613  header.group_element = info->old_group_element;
1614  if (!scan(&header, &pofs)) {
1615  // the old parameter isn't saved in the EEPROM.
1616  return false;
1617  }
1618 
1619  // load the old value from EEPROM
1620  _storage.read_block(value, pofs+sizeof(header), type_size((enum ap_var_type)header.type));
1621  return true;
1622 }
1623 
1624 
1625 #pragma GCC diagnostic push
1626 #pragma GCC diagnostic ignored "-Wformat"
1627 // convert one old vehicle parameter to new object parameter
1628 void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags)
1629 {
1630  uint8_t old_value[type_size(info->type)];
1631  AP_Param *ap = (AP_Param *)&old_value[0];
1632 
1633  if (!find_old_parameter(info, ap)) {
1634  // the old parameter isn't saved in the EEPROM. It was
1635  // probably still set to the default value, which isn't stored
1636  // no need to convert
1637  return;
1638  }
1639 
1640  // find the new variable in the variable structures
1641  enum ap_var_type ptype;
1642  AP_Param *ap2;
1643  ap2 = find(&info->new_name[0], &ptype);
1644  if (ap2 == nullptr) {
1645  hal.console->printf("Unknown conversion '%s'\n", info->new_name);
1646  return;
1647  }
1648 
1649  // see if we can load it from EEPROM
1650  if (!(flags & CONVERT_FLAG_FORCE) && ap2->configured_in_storage()) {
1651  // the new parameter already has a value set by the user, or
1652  // has already been converted
1653  return;
1654  }
1655 
1656  // see if they are the same type and no scaling applied
1657  if (ptype == info->type && is_equal(scaler, 1.0f) && flags == 0) {
1658  // copy the value over only if the new parameter does not already
1659  // have the old value (via a default).
1660  if (memcmp(ap2, ap, sizeof(old_value)) != 0) {
1661  memcpy(ap2, ap, sizeof(old_value));
1662  // and save
1663  ap2->save();
1664  }
1665  } else if (ptype <= AP_PARAM_FLOAT && info->type <= AP_PARAM_FLOAT) {
1666  // perform scalar->scalar conversion
1667  float v = ap->cast_to_float(info->type);
1668  if (flags & CONVERT_FLAG_REVERSE) {
1669  // convert a _REV parameter to a _REVERSED parameter
1670  v = is_equal(v, -1.0f)?1:0;
1671  }
1672  if (!is_equal(v,ap2->cast_to_float(ptype))) {
1673  // the value needs to change
1674  set_value(ptype, ap2, v * scaler);
1675  ap2->save();
1676  }
1677  } else {
1678  // can't do vector<->scalar conversion, or different vector types
1679  hal.console->printf("Bad conversion type '%s'\n", info->new_name);
1680  }
1681 }
1682 #pragma GCC diagnostic pop
1683 
1684 
1685 // convert old vehicle parameters to new object parametersv
1686 void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags)
1687 {
1688  for (uint8_t i=0; i<table_size; i++) {
1689  convert_old_parameter(&conversion_table[i], 1.0f, flags);
1690  }
1691 }
1692 
1693 /*
1694  move old class variables for a class that was sub-classed to one that isn't
1695  For example, used when the AP_MotorsTri class changed from having its own parameter table
1696  plus a subgroup for AP_MotorsMulticopter to just inheriting the AP_MotorsMulticopter var_info
1697 
1698  This does not handle nesting beyond the single level shift
1699 */
1700 void AP_Param::convert_parent_class(uint8_t param_key, void *object_pointer,
1701  const struct AP_Param::GroupInfo *group_info)
1702 {
1703  for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
1704  struct ConversionInfo info;
1705  info.old_key = param_key;
1706  info.type = (ap_var_type)group_info[i].type;
1707  info.new_name = nullptr;
1708  info.old_group_element = uint16_t(group_info[i].idx)<<6;
1709  uint8_t old_value[type_size(info.type)];
1710  AP_Param *ap = (AP_Param *)&old_value[0];
1711 
1712  if (!AP_Param::find_old_parameter(&info, ap)) {
1713  // the parameter wasn't set in the old eeprom
1714  continue;
1715  }
1716 
1717  uint8_t *new_value = group_info[i].offset + (uint8_t *)object_pointer;
1718  memcpy(new_value, old_value, sizeof(old_value));
1719  }
1720 }
1721 
1722 
1723 /*
1724  set a parameter to a float value
1725  */
1726 void AP_Param::set_float(float value, enum ap_var_type var_type)
1727 {
1728  if (isnan(value) || isinf(value)) {
1729  return;
1730  }
1731 
1732  // add a small amount before casting parameter values
1733  // from float to integer to avoid truncating to the
1734  // next lower integer value.
1735  float rounding_addition = 0.01f;
1736 
1737  // handle variables with standard type IDs
1738  if (var_type == AP_PARAM_FLOAT) {
1739  ((AP_Float *)this)->set(value);
1740  } else if (var_type == AP_PARAM_INT32) {
1741  if (value < 0) rounding_addition = -rounding_addition;
1742  float v = value+rounding_addition;
1743  v = constrain_float(v, -2147483648.0, 2147483647.0);
1744  ((AP_Int32 *)this)->set(v);
1745  } else if (var_type == AP_PARAM_INT16) {
1746  if (value < 0) rounding_addition = -rounding_addition;
1747  float v = value+rounding_addition;
1748  v = constrain_float(v, -32768, 32767);
1749  ((AP_Int16 *)this)->set(v);
1750  } else if (var_type == AP_PARAM_INT8) {
1751  if (value < 0) rounding_addition = -rounding_addition;
1752  float v = value+rounding_addition;
1753  v = constrain_float(v, -128, 127);
1754  ((AP_Int8 *)this)->set(v);
1755  }
1756 }
1757 
1758 
1759 /*
1760  parse a parameter file line
1761  */
1762 bool AP_Param::parse_param_line(char *line, char **vname, float &value)
1763 {
1764  if (line[0] == '#') {
1765  return false;
1766  }
1767  char *saveptr = nullptr;
1768  char *pname = strtok_r(line, ", =\t", &saveptr);
1769  if (pname == nullptr) {
1770  return false;
1771  }
1772  if (strlen(pname) > AP_MAX_NAME_SIZE) {
1773  return false;
1774  }
1775  const char *value_s = strtok_r(nullptr, ", =\t", &saveptr);
1776  if (value_s == nullptr) {
1777  return false;
1778  }
1779  value = atof(value_s);
1780  *vname = pname;
1781  return true;
1782 }
1783 
1784 
1785 #if HAL_OS_POSIX_IO == 1
1786 #include <stdio.h>
1787 
1788 // increments num_defaults for each default found in filename
1789 bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults, bool panic_on_error)
1790 {
1791  FILE *f = fopen(filename, "r");
1792  if (f == nullptr) {
1793  return false;
1794  }
1795  char line[100];
1796 
1797  /*
1798  work out how many parameter default structures to allocate
1799  */
1800  while (fgets(line, sizeof(line)-1, f)) {
1801  char *pname;
1802  float value;
1803  if (!parse_param_line(line, &pname, value)) {
1804  continue;
1805  }
1806  enum ap_var_type var_type;
1807  if (!find(pname, &var_type)) {
1808  if (panic_on_error) {
1809  fclose(f);
1810  ::printf("invalid param %s in defaults file\n", pname);
1811  AP_HAL::panic("AP_Param: Invalid param in defaults file");
1812  return false;
1813  } else {
1814  continue;
1815  }
1816  }
1817  num_defaults++;
1818  }
1819  fclose(f);
1820 
1821  return true;
1822 }
1823 
1824 bool AP_Param::read_param_defaults_file(const char *filename)
1825 {
1826  FILE *f = fopen(filename, "r");
1827  if (f == nullptr) {
1828  AP_HAL::panic("AP_Param: Failed to re-open defaults file");
1829  return false;
1830  }
1831 
1832  uint16_t idx = 0;
1833  char line[100];
1834  while (fgets(line, sizeof(line)-1, f)) {
1835  char *pname;
1836  float value;
1837  if (!parse_param_line(line, &pname, value)) {
1838  continue;
1839  }
1840  enum ap_var_type var_type;
1841  AP_Param *vp = find(pname, &var_type);
1842  if (!vp) {
1843  continue;
1844  }
1845  param_overrides[idx].object_ptr = vp;
1846  param_overrides[idx].value = value;
1847  idx++;
1848  if (!vp->configured_in_storage()) {
1849  vp->set_float(value, var_type);
1850  }
1851  }
1852  fclose(f);
1853  return true;
1854 }
1855 
1856 /*
1857  load a default set of parameters from a file
1858  */
1859 bool AP_Param::load_defaults_file(const char *filename, bool panic_on_error)
1860 {
1861  if (filename == nullptr) {
1862  return false;
1863  }
1864 
1865  char *mutable_filename = strdup(filename);
1866  if (mutable_filename == nullptr) {
1867  AP_HAL::panic("AP_Param: Failed to allocate mutable string");
1868  }
1869 
1870  uint16_t num_defaults = 0;
1871  char *saveptr = nullptr;
1872  for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
1873  pname != nullptr;
1874  pname = strtok_r(nullptr, ",", &saveptr)) {
1875  if (!count_defaults_in_file(pname, num_defaults, panic_on_error)) {
1876  free(mutable_filename);
1877  return false;
1878  }
1879  }
1880  free(mutable_filename);
1881 
1882  if (param_overrides != nullptr) {
1884  }
1885  num_param_overrides = 0;
1886 
1887  param_overrides = new param_override[num_defaults];
1888  if (param_overrides == nullptr) {
1889  AP_HAL::panic("AP_Param: Failed to allocate overrides");
1890  return false;
1891  }
1892 
1893  saveptr = nullptr;
1894  mutable_filename = strdup(filename);
1895  if (mutable_filename == nullptr) {
1896  AP_HAL::panic("AP_Param: Failed to allocate mutable string");
1897  }
1898  for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
1899  pname != nullptr;
1900  pname = strtok_r(nullptr, ",", &saveptr)) {
1901  if (!read_param_defaults_file(pname)) {
1902  free(mutable_filename);
1903  return false;
1904  }
1905  }
1906  free(mutable_filename);
1907 
1908  num_param_overrides = num_defaults;
1909 
1910  return true;
1911 }
1912 
1913 #endif // HAL_OS_POSIX_IO
1914 
1915 /*
1916  count the number of embedded parameter defaults
1917  */
1918 bool AP_Param::count_embedded_param_defaults(uint16_t &count, bool panic_on_error)
1919 {
1920  const volatile char *ptr = param_defaults_data.data;
1921  uint16_t length = param_defaults_data.length;
1922  count = 0;
1923 
1924  while (length) {
1925  char line[100];
1926  char *pname;
1927  float value;
1928  uint16_t i;
1929  uint16_t n = MIN(length, sizeof(line)-1);
1930  for (i=0;i<n;i++) {
1931  if (ptr[i] == '\n') {
1932  break;
1933  }
1934  }
1935  if (i == n) {
1936  // no newline
1937  break;
1938  }
1939 
1940  memcpy(line, (void *)ptr, i);
1941  line[i] = 0;
1942 
1943  length -= i+1;
1944  ptr += i+1;
1945 
1946  if (line[0] == '#' || line[0] == 0) {
1947  continue;
1948  }
1949 
1950  if (!parse_param_line(line, &pname, value)) {
1951  continue;
1952  }
1953 
1954  enum ap_var_type var_type;
1955  if (!find(pname, &var_type)) {
1956  if (panic_on_error) {
1957  ::printf("invalid param %s in defaults file\n", pname);
1958  AP_HAL::panic("AP_Param: Invalid param in embedded defaults");
1959  } else {
1960  continue;
1961  }
1962  }
1963  count++;
1964  }
1965  return true;
1966 }
1967 
1968 
1969 /*
1970  load a default set of parameters from a embedded parameter region
1971  */
1973 {
1974  if (param_overrides != nullptr) {
1976  param_overrides = nullptr;
1977  }
1978 
1979  num_param_overrides = 0;
1980  uint16_t num_defaults = 0;
1981  if (!count_embedded_param_defaults(num_defaults, panic_on_error)) {
1982  return;
1983  }
1984 
1985  param_overrides = new param_override[num_defaults];
1986  if (param_overrides == nullptr) {
1987  AP_HAL::panic("AP_Param: Failed to allocate overrides");
1988  return;
1989  }
1990 
1991  const volatile char *ptr = param_defaults_data.data;
1992  uint16_t length = param_defaults_data.length;
1993  uint16_t idx = 0;
1994 
1995  while (length) {
1996  char line[100];
1997  char *pname;
1998  float value;
1999  uint16_t i;
2000  uint16_t n = MIN(length, sizeof(line)-1);
2001  for (i=0;i<n;i++) {
2002  if (ptr[i] == '\n') {
2003  break;
2004  }
2005  }
2006  if (i == n) {
2007  // no newline
2008  break;
2009  }
2010  memcpy(line, (void*)ptr, i);
2011  line[i] = 0;
2012 
2013  length -= i+1;
2014  ptr += i+1;
2015 
2016  if (line[0] == '#' || line[0] == 0) {
2017  continue;
2018  }
2019 
2020  if (!parse_param_line(line, &pname, value)) {
2021  continue;
2022  }
2023  enum ap_var_type var_type;
2024  AP_Param *vp = find(pname, &var_type);
2025  if (!vp) {
2026  continue;
2027  }
2028  param_overrides[idx].object_ptr = vp;
2029  param_overrides[idx].value = value;
2030  idx++;
2031  if (!vp->configured_in_storage()) {
2032  vp->set_float(value, var_type);
2033  }
2034  }
2035  num_param_overrides = num_defaults;
2036 }
2037 
2038 /*
2039  find a default value given a pointer to a default value in flash
2040  */
2041 float AP_Param::get_default_value(const AP_Param *vp, const float *def_value_ptr)
2042 {
2043  for (uint16_t i=0; i<num_param_overrides; i++) {
2044  if (vp == param_overrides[i].object_ptr) {
2045  return param_overrides[i].value;
2046  }
2047  }
2048  return *def_value_ptr;
2049 }
2050 
2051 
2052 void AP_Param::send_parameter(const char *name, enum ap_var_type var_type, uint8_t idx) const
2053 {
2054  if (idx != 0 && var_type == AP_PARAM_VECTOR3F) {
2055  var_type = AP_PARAM_FLOAT;
2056  }
2057  if (var_type > AP_PARAM_VECTOR3F) {
2058  // invalid
2059  return;
2060  }
2061  if (var_type != AP_PARAM_VECTOR3F) {
2062  // nice and simple for scalar types
2063  gcs().send_parameter_value(name, var_type, cast_to_float(var_type));
2064  return;
2065  }
2066 
2067  // for vectors we need to send 3 messages. Note that we also come here for the case
2068  // of a set of the first element of a AP_Vector3f. This happens as the ap->save() call can't
2069  // distinguish between a vector and scalar save. It means that setting first element of a vector
2070  // via MAVLink results in sending all 3 elements to the GCS
2071  const Vector3f &v = ((AP_Vector3f *)this)->get();
2072  char name2[AP_MAX_NAME_SIZE+1];
2073  strncpy(name2, name, AP_MAX_NAME_SIZE);
2074  name2[AP_MAX_NAME_SIZE] = 0;
2075  char &name_axis = name2[strlen(name)-1];
2076 
2077  name_axis = 'X';
2079  name_axis = 'Y';
2081  name_axis = 'Z';
2083 }
2084 
2085 /*
2086  return count of all scalar parameters.
2087  Note that this function may be called from the IO thread, so needs
2088  to be thread safe
2089  */
2091 {
2092  // if we haven't cached the parameter count yet...
2093  uint16_t ret = _parameter_count;
2094  if (0 == ret) {
2095  AP_Param *vp;
2096  AP_Param::ParamToken token;
2097 
2098  for (vp = AP_Param::first(&token, nullptr);
2099  vp != nullptr;
2100  vp = AP_Param::next_scalar(&token, nullptr)) {
2101  ret++;
2102  }
2103  _parameter_count = ret;
2104  }
2105  return ret;
2106 }
2107 
2108 /*
2109  set a default value by name
2110  */
2111 bool AP_Param::set_default_by_name(const char *name, float value)
2112 {
2113  enum ap_var_type vtype;
2114  AP_Param *vp = find(name, &vtype);
2115  if (vp == nullptr) {
2116  return false;
2117  }
2118  switch (vtype) {
2119  case AP_PARAM_INT8:
2120  ((AP_Int8 *)vp)->set_default(value);
2121  return true;
2122  case AP_PARAM_INT16:
2123  ((AP_Int16 *)vp)->set_default(value);
2124  return true;
2125  case AP_PARAM_INT32:
2126  ((AP_Int32 *)vp)->set_default(value);
2127  return true;
2128  case AP_PARAM_FLOAT:
2129  ((AP_Float *)vp)->set_default(value);
2130  return true;
2131  default:
2132  break;
2133  }
2134  // not a supported type
2135  return false;
2136 }
2137 
2138 /*
2139  set a value by name
2140  */
2141 bool AP_Param::set_by_name(const char *name, float value)
2142 {
2143  enum ap_var_type vtype;
2144  AP_Param *vp = find(name, &vtype);
2145  if (vp == nullptr) {
2146  return false;
2147  }
2148  switch (vtype) {
2149  case AP_PARAM_INT8:
2150  ((AP_Int8 *)vp)->set(value);
2151  return true;
2152  case AP_PARAM_INT16:
2153  ((AP_Int16 *)vp)->set(value);
2154  return true;
2155  case AP_PARAM_INT32:
2156  ((AP_Int32 *)vp)->set(value);
2157  return true;
2158  case AP_PARAM_FLOAT:
2159  ((AP_Float *)vp)->set(value);
2160  return true;
2161  default:
2162  break;
2163  }
2164  // not a supported type
2165  return false;
2166 }
2167 
2168 /*
2169  set and save a value by name
2170  */
2172 {
2173  enum ap_var_type vtype;
2174  AP_Param *vp = find(name, &vtype);
2175  if (vp == nullptr) {
2176  return false;
2177  }
2178  switch (vtype) {
2179  case AP_PARAM_INT8:
2180  ((AP_Int8 *)vp)->set_and_save(value);
2181  return true;
2182  case AP_PARAM_INT16:
2183  ((AP_Int16 *)vp)->set_and_save(value);
2184  return true;
2185  case AP_PARAM_INT32:
2186  ((AP_Int32 *)vp)->set_and_save(value);
2187  return true;
2188  case AP_PARAM_FLOAT:
2189  ((AP_Float *)vp)->set_and_save(value);
2190  return true;
2191  default:
2192  break;
2193  }
2194  // not a supported type
2195  return false;
2196 }
2197 
2198 #if AP_PARAM_KEY_DUMP
2199 /*
2200  do not remove this show_all() code, it is essential for debugging
2201  and creating conversion tables
2202  */
2203 
2204 // print the value of all variables
2205 void AP_Param::show(const AP_Param *ap, const char *s,
2206  enum ap_var_type type, AP_HAL::BetterStream *port)
2207 {
2208  switch (type) {
2209  case AP_PARAM_INT8:
2210  port->printf("%s: %d\n", s, (int)((AP_Int8 *)ap)->get());
2211  break;
2212  case AP_PARAM_INT16:
2213  port->printf("%s: %d\n", s, (int)((AP_Int16 *)ap)->get());
2214  break;
2215  case AP_PARAM_INT32:
2216  port->printf("%s: %ld\n", s, (long)((AP_Int32 *)ap)->get());
2217  break;
2218  case AP_PARAM_FLOAT:
2219  port->printf("%s: %f\n", s, (double)((AP_Float *)ap)->get());
2220  break;
2221  default:
2222  break;
2223  }
2224 }
2225 
2226 // print the value of all variables
2227 void AP_Param::show(const AP_Param *ap, const ParamToken &token,
2228  enum ap_var_type type, AP_HAL::BetterStream *port)
2229 {
2230  char s[AP_MAX_NAME_SIZE+1];
2231  ap->copy_name_token(token, s, sizeof(s), true);
2232  s[AP_MAX_NAME_SIZE] = 0;
2233  show(ap, s, type, port);
2234 }
2235 
2236 // print the value of all variables
2237 void AP_Param::show_all(AP_HAL::BetterStream *port, bool showKeyValues)
2238 {
2239  ParamToken token;
2240  AP_Param *ap;
2241  enum ap_var_type type;
2242 
2243  for (ap=AP_Param::first(&token, &type);
2244  ap;
2245  ap=AP_Param::next_scalar(&token, &type)) {
2246  if (showKeyValues) {
2247  port->printf("Key %i: Index %i: GroupElement %i : ", token.key, token.idx, token.group_element);
2248  }
2249  show(ap, token, type, port);
2250  }
2251 }
2252 #endif // AP_PARAM_KEY_DUMP
2253 
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
int printf(const char *fmt,...)
Definition: stdio.c:113
uint32_t group_element
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
#define AP_PARAM_FLAG_INFO_POINTER
Definition: AP_Param.h:63
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
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1335
#define AP_PARAM_FLAG_POINTER
Definition: AP_Param.h:52
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
#define AP_MAX_NAME_SIZE
Definition: AP_Param.h:32
static bool get_base(const struct Info &info, ptrdiff_t &base)
Definition: AP_Param.cpp:353
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
#define AP_PARAM_FLAG_NESTED_OFFSET
Definition: AP_Param.h:49
static void set_key(Param_header &phdr, uint16_t key)
Definition: AP_Param.cpp:634
AP_HAL::UARTDriver * console
Definition: HAL.h:110
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
uint32_t key
Interface definition for the various Ground Control System.
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
void send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
Definition: GCS_Param.cpp:325
const struct GroupInfo * group_ret[numlevels]
Definition: AP_Param.h:205
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
uint16_t size(void) const
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
static AP_Param * find(const char *name, enum ap_var_type *ptype)
Definition: AP_Param.cpp:821
AP_HAL::Util * util
Definition: HAL.h:115
static bool duplicate_key(uint16_t vindex, uint16_t key)
Definition: AP_Param.cpp:215
static const uint8_t numlevels
Definition: AP_Param.h:203
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
GCS & gcs()
static const uint8_t _group_level_shift
Definition: AP_Param.h:470
ptrdiff_t offset
Definition: AP_Param.h:149
const char * name
Definition: BusTest.cpp:11
uint16_t key
Definition: AP_Param.h:160
const struct GroupInfo * group_info
Definition: AP_Param.h:163
#define MIN(a, b)
Definition: usb_conf.h:215
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
A system for managing and storing variables that are of general interest to the system.
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
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
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
#define Debug(fmt, args ...)
Definition: AP_Param.cpp:41
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
#define AP_PARAM_NO_SHIFT
Definition: AP_Param.h:60
#define f(i)
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
T y
Definition: vector3.h:67
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
T z
Definition: vector3.h:67
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 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
#define AP_PARAM_FRAME_TYPE_SHIFT
Definition: AP_Param.h:74
bool read_block(void *dst, uint16_t src, size_t n) const
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
#define AP_PARAM_FLAG_IGNORE_ENABLE
Definition: AP_Param.h:66
void free(void *ptr)
Definition: malloc.c:81
Common definitions and utility routines for the ArduPilot libraries.
virtual const char * get_custom_defaults_file() const
Definition: Util.h:26
static bool initialised(void)
Definition: AP_Param.cpp:315
static const param_defaults_struct param_defaults_data
Definition: AP_Param.h:489
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
static void reload_defaults_file(bool panic_on_error=true)
Definition: AP_Param.cpp:1307
volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM]
Definition: AP_Param.h:487
static const uint16_t _sentinal_key
Definition: AP_Param.h:473
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
Definition: posix.c:772
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
Definition: AP_Param.cpp:1587
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static uint8_t type_size(enum ap_var_type type)
Definition: AP_Param.cpp:602
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
const struct GroupInfo * group_info
Definition: AP_Param.h:151
uint32_t old_group_element
Definition: AP_Param.h:171
bool write_block(uint16_t dst, const void *src, size_t n) const
static void write_sentinal(uint16_t ofs)
Definition: AP_Param.cpp:98
enum ap_var_type type
Definition: AP_Param.h:172
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
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
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
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
uint32_t type
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
char * fgets(char *str, int size, FILE *stream)
get a string from stdin See fdevopen() sets stream->put get for TTY devices
Definition: posix.c:398
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
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0)
Definition: AP_Param.cpp:1686
T x
Definition: vector3.h:67
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