Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- |
2 | // |
||
3 | // This is free software; you can redistribute it and/or modify it under |
||
4 | // the terms of the GNU Lesser General Public License as published by the |
||
5 | // Free Software Foundation; either version 2.1 of the License, or (at |
||
6 | // your option) any later version. |
||
7 | // |
||
8 | |||
9 | // total up and check overflow |
||
10 | // check size of group var_info |
||
11 | |||
12 | /// @file AP_Param.cpp |
||
13 | /// @brief The AP variable store. |
||
14 | |||
15 | |||
16 | #include <FastSerial.h> |
||
17 | #include <AP_Common.h> |
||
18 | #include <AP_Math.h> |
||
19 | |||
20 | #include <math.h> |
||
21 | #include <string.h> |
||
22 | |||
23 | // #define ENABLE_FASTSERIAL_DEBUG |
||
24 | |||
25 | #ifdef ENABLE_FASTSERIAL_DEBUG |
||
26 | # define serialDebug(fmt, args...) if (FastSerial::getInitialized(0)) do {Serial.printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__ , ##args); delay(0); } while(0) |
||
27 | #else |
||
28 | # define serialDebug(fmt, args...) |
||
29 | #endif |
||
30 | |||
31 | // some useful progmem macros |
||
32 | #define PGM_UINT8(addr) pgm_read_byte((const prog_char *)addr) |
||
33 | #define PGM_UINT16(addr) pgm_read_word((const uint16_t *)addr) |
||
34 | #define PGM_POINTER(addr) pgm_read_pointer((const void *)addr) |
||
35 | |||
36 | // the 'GROUP_ID' of a element of a group is the 8 bit identifier used |
||
37 | // to distinguish between this element of the group and other elements |
||
38 | // of the same group. It is calculated using a bit shift per level of |
||
39 | // nesting, so the first level of nesting gets 4 bits, and the next |
||
40 | // level gets the next 4 bits. This limits groups to having at most 16 |
||
41 | // elements. |
||
42 | #define GROUP_ID(grpinfo, base, i, shift) ((base)+(((uint16_t)PGM_UINT8(&grpinfo[i].idx))<<(shift))) |
||
43 | |||
44 | // Note about AP_Vector3f handling. |
||
45 | // The code has special cases for AP_Vector3f to allow it to be viewed |
||
46 | // as both a single 3 element vector and as a set of 3 AP_Float |
||
47 | // variables. This is done to make it possible for MAVLink to see |
||
48 | // vectors as parameters, which allows users to save their compass |
||
49 | // offsets in MAVLink parameter files. The code involves quite a few |
||
50 | // special cases which could be generalised to any vector/matrix type |
||
51 | // if we end up needing this behaviour for other than AP_Vector3f |
||
52 | |||
53 | |||
54 | // static member variables for AP_Param. |
||
55 | // |
||
56 | |||
57 | // max EEPROM write size. This is usually less than the physical |
||
58 | // size as only part of the EEPROM is reserved for parameters |
||
59 | uint16_t AP_Param::_eeprom_size; |
||
60 | |||
61 | // number of rows in the _var_info[] table |
||
62 | uint8_t AP_Param::_num_vars; |
||
63 | |||
64 | // storage and naming information about all types that can be saved |
||
65 | const AP_Param::Info *AP_Param::_var_info; |
||
66 | |||
67 | // write to EEPROM, checking each byte to avoid writing |
||
68 | // bytes that are already correct |
||
69 | void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size) |
||
70 | { |
||
71 | const uint8_t *b = (const uint8_t *)ptr; |
||
72 | while (size--) { |
||
73 | uint8_t v = eeprom_read_byte((const uint8_t *)ofs); |
||
74 | if (v != *b) { |
||
75 | eeprom_write_byte((uint8_t *)ofs, *b); |
||
76 | } |
||
77 | b++; |
||
78 | ofs++; |
||
79 | } |
||
80 | } |
||
81 | |||
82 | // write a sentinal value at the given offset |
||
83 | void AP_Param::write_sentinal(uint16_t ofs) |
||
84 | { |
||
85 | struct Param_header phdr; |
||
86 | phdr.type = _sentinal_type; |
||
87 | phdr.key = _sentinal_key; |
||
88 | phdr.group_element = _sentinal_group; |
||
89 | eeprom_write_check(&phdr, ofs, sizeof(phdr)); |
||
90 | } |
||
91 | |||
92 | // erase all EEPROM variables by re-writing the header and adding |
||
93 | // a sentinal |
||
94 | void AP_Param::erase_all(void) |
||
95 | { |
||
96 | struct EEPROM_header hdr; |
||
97 | |||
98 | serialDebug("erase_all"); |
||
99 | |||
100 | // write the header |
||
101 | hdr.magic[0] = k_EEPROM_magic0; |
||
102 | hdr.magic[1] = k_EEPROM_magic1; |
||
103 | hdr.revision = k_EEPROM_revision; |
||
104 | hdr.spare = 0; |
||
105 | eeprom_write_check(&hdr, 0, sizeof(hdr)); |
||
106 | |||
107 | // add a sentinal directly after the header |
||
108 | write_sentinal(sizeof(struct EEPROM_header)); |
||
109 | } |
||
110 | |||
111 | // validate a group info table |
||
112 | bool AP_Param::check_group_info(const struct AP_Param::GroupInfo *group_info, |
||
113 | uint16_t *total_size, |
||
114 | uint8_t group_shift) |
||
115 | { |
||
116 | uint8_t type; |
||
117 | int8_t max_idx = -1; |
||
118 | for (uint8_t i=0; |
||
119 | (type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; |
||
120 | i++) { |
||
121 | #ifdef AP_NESTED_GROUPS_ENABLED |
||
122 | if (type == AP_PARAM_GROUP) { |
||
123 | // a nested group |
||
124 | const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info); |
||
125 | if (group_shift + _group_level_shift >= _group_bits) { |
||
126 | // double nesting of groups is not allowed |
||
127 | return false; |
||
128 | } |
||
129 | if (ginfo == NULL || |
||
130 | !check_group_info(ginfo, total_size, group_shift + _group_level_shift)) { |
||
131 | return false; |
||
132 | } |
||
133 | continue; |
||
134 | } |
||
135 | #endif // AP_NESTED_GROUPS_ENABLED |
||
136 | uint8_t idx = PGM_UINT8(&group_info[i].idx); |
||
137 | if (idx >= (1<<_group_level_shift)) { |
||
138 | // passed limit on table size |
||
139 | return false; |
||
140 | } |
||
141 | if ((int8_t)idx <= max_idx) { |
||
142 | // the indexes must be in increasing order |
||
143 | return false; |
||
144 | } |
||
145 | max_idx = (int8_t)idx; |
||
146 | uint8_t size = type_size((enum ap_var_type)type); |
||
147 | if (size == 0) { |
||
148 | // not a valid type |
||
149 | return false; |
||
150 | } |
||
151 | (*total_size) += size + sizeof(struct Param_header); |
||
152 | } |
||
153 | return true; |
||
154 | } |
||
155 | |||
156 | // check for duplicate key values |
||
157 | bool AP_Param::duplicate_key(uint8_t vindex, uint8_t key) |
||
158 | { |
||
159 | for (uint8_t i=vindex+1; i<_num_vars; i++) { |
||
160 | uint8_t key2 = PGM_UINT8(&_var_info[i].key); |
||
161 | if (key2 == key) { |
||
162 | // no duplicate keys allowed |
||
163 | return true; |
||
164 | } |
||
165 | } |
||
166 | return false; |
||
167 | } |
||
168 | |||
169 | // validate the _var_info[] table |
||
170 | bool AP_Param::check_var_info(void) |
||
171 | { |
||
172 | uint16_t total_size = sizeof(struct EEPROM_header); |
||
173 | |||
174 | for (uint8_t i=0; i<_num_vars; i++) { |
||
175 | uint8_t type = PGM_UINT8(&_var_info[i].type); |
||
176 | uint8_t key = PGM_UINT8(&_var_info[i].key); |
||
177 | if (type == AP_PARAM_GROUP) { |
||
178 | if (i == 0) { |
||
179 | // first element can't be a group, for first() call |
||
180 | return false; |
||
181 | } |
||
182 | const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info); |
||
183 | if (group_info == NULL || |
||
184 | !check_group_info(group_info, &total_size, 0)) { |
||
185 | return false; |
||
186 | } |
||
187 | } else { |
||
188 | uint8_t size = type_size((enum ap_var_type)type); |
||
189 | if (size == 0) { |
||
190 | // not a valid type - the top level list can't contain |
||
191 | // AP_PARAM_NONE |
||
192 | return false; |
||
193 | } |
||
194 | total_size += size + sizeof(struct Param_header); |
||
195 | } |
||
196 | if (duplicate_key(i, key)) { |
||
197 | return false; |
||
198 | } |
||
199 | } |
||
200 | if (total_size > _eeprom_size) { |
||
201 | serialDebug("total_size %u exceeds _eeprom_size %u", |
||
202 | total_size, _eeprom_size); |
||
203 | return false; |
||
204 | } |
||
205 | return true; |
||
206 | } |
||
207 | |||
208 | |||
209 | // setup the _var_info[] table |
||
210 | bool AP_Param::setup(const AP_Param::Info *info, uint8_t num_vars, uint16_t eeprom_size) |
||
211 | { |
||
212 | struct EEPROM_header hdr; |
||
213 | |||
214 | _eeprom_size = eeprom_size; |
||
215 | _var_info = info; |
||
216 | _num_vars = num_vars; |
||
217 | |||
218 | if (!check_var_info()) { |
||
219 | return false; |
||
220 | } |
||
221 | |||
222 | serialDebug("setup %u vars", (unsigned)num_vars); |
||
223 | |||
224 | // check the header |
||
225 | eeprom_read_block(&hdr, 0, sizeof(hdr)); |
||
226 | if (hdr.magic[0] != k_EEPROM_magic0 || |
||
227 | hdr.magic[1] != k_EEPROM_magic1 || |
||
228 | hdr.revision != k_EEPROM_revision) { |
||
229 | // header doesn't match. We can't recover any variables. Wipe |
||
230 | // the header and setup the sentinal directly after the header |
||
231 | serialDebug("bad header in setup - erasing"); |
||
232 | erase_all(); |
||
233 | } |
||
234 | |||
235 | return true; |
||
236 | } |
||
237 | |||
238 | // check if AP_Param has been initialised |
||
239 | bool AP_Param::initialised(void) |
||
240 | { |
||
241 | return _var_info != NULL; |
||
242 | } |
||
243 | |||
244 | // find the info structure given a header and a group_info table |
||
245 | // return the Info structure and a pointer to the variables storage |
||
246 | const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header phdr, void **ptr, |
||
247 | uint8_t vindex, |
||
248 | const struct GroupInfo *group_info, |
||
249 | uint8_t group_base, |
||
250 | uint8_t group_shift) |
||
251 | { |
||
252 | uint8_t type; |
||
253 | for (uint8_t i=0; |
||
254 | (type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; |
||
255 | i++) { |
||
256 | #ifdef AP_NESTED_GROUPS_ENABLED |
||
257 | if (type == AP_PARAM_GROUP) { |
||
258 | // a nested group |
||
259 | if (group_shift + _group_level_shift >= _group_bits) { |
||
260 | // too deeply nested - this should have been caught by |
||
261 | // setup() ! |
||
262 | return NULL; |
||
263 | } |
||
264 | const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info); |
||
265 | const struct AP_Param::Info *ret = find_by_header_group(phdr, ptr, vindex, ginfo, |
||
266 | GROUP_ID(group_info, group_base, i, group_shift), |
||
267 | group_shift + _group_level_shift); |
||
268 | if (ret != NULL) { |
||
269 | return ret; |
||
270 | } |
||
271 | continue; |
||
272 | } |
||
273 | #endif // AP_NESTED_GROUPS_ENABLED |
||
274 | if (GROUP_ID(group_info, group_base, i, group_shift) == phdr.group_element) { |
||
275 | // found a group element |
||
276 | *ptr = (void*)(PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset)); |
||
277 | return &_var_info[vindex]; |
||
278 | } |
||
279 | } |
||
280 | return NULL; |
||
281 | } |
||
282 | |||
283 | // find the info structure given a header |
||
284 | // return the Info structure and a pointer to the variables storage |
||
285 | const struct AP_Param::Info *AP_Param::find_by_header(struct Param_header phdr, void **ptr) |
||
286 | { |
||
287 | // loop over all named variables |
||
288 | for (uint8_t i=0; i<_num_vars; i++) { |
||
289 | uint8_t type = PGM_UINT8(&_var_info[i].type); |
||
290 | uint8_t key = PGM_UINT8(&_var_info[i].key); |
||
291 | if (key != phdr.key) { |
||
292 | // not the right key |
||
293 | continue; |
||
294 | } |
||
295 | if (type != AP_PARAM_GROUP) { |
||
296 | // if its not a group then we are done |
||
297 | *ptr = (void*)PGM_POINTER(&_var_info[i].ptr); |
||
298 | return &_var_info[i]; |
||
299 | } |
||
300 | |||
301 | const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info); |
||
302 | return find_by_header_group(phdr, ptr, i, group_info, 0, 0); |
||
303 | } |
||
304 | return NULL; |
||
305 | } |
||
306 | |||
307 | // find the info structure for a variable in a group |
||
308 | const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInfo *group_info, |
||
309 | uint8_t vindex, |
||
310 | uint8_t group_base, |
||
311 | uint8_t group_shift, |
||
312 | uint8_t *group_element, |
||
313 | const struct GroupInfo **group_ret, |
||
314 | uint8_t *idx) |
||
315 | { |
||
316 | uintptr_t base = PGM_POINTER(&_var_info[vindex].ptr); |
||
317 | uint8_t type; |
||
318 | for (uint8_t i=0; |
||
319 | (type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; |
||
320 | i++) { |
||
321 | uintptr_t ofs = PGM_POINTER(&group_info[i].offset); |
||
322 | #ifdef AP_NESTED_GROUPS_ENABLED |
||
323 | if (type == AP_PARAM_GROUP) { |
||
324 | const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info); |
||
325 | // a nested group |
||
326 | if (group_shift + _group_level_shift >= _group_bits) { |
||
327 | // too deeply nested - this should have been caught by |
||
328 | // setup() ! |
||
329 | return NULL; |
||
330 | } |
||
331 | const struct AP_Param::Info *info; |
||
332 | info = find_var_info_group(ginfo, vindex, |
||
333 | GROUP_ID(group_info, group_base, i, group_shift), |
||
334 | group_shift + _group_level_shift, |
||
335 | group_element, |
||
336 | group_ret, |
||
337 | idx); |
||
338 | if (info != NULL) { |
||
339 | return info; |
||
340 | } |
||
341 | } else // Forgive the poor formatting - if continues below. |
||
342 | #endif // AP_NESTED_GROUPS_ENABLED |
||
343 | if ((uintptr_t)this == base + ofs) { |
||
344 | *group_element = GROUP_ID(group_info, group_base, i, group_shift); |
||
345 | *group_ret = &group_info[i]; |
||
346 | *idx = 0; |
||
347 | return &_var_info[vindex]; |
||
348 | } else if (type == AP_PARAM_VECTOR3F && |
||
349 | (base+ofs+sizeof(float) == (uintptr_t)this || |
||
350 | base+ofs+2*sizeof(float) == (uintptr_t)this)) { |
||
351 | // we are inside a Vector3f. We need to work out which |
||
352 | // element of the vector the current object refers to. |
||
353 | *idx = (((uintptr_t)this) - (base+ofs))/sizeof(float); |
||
354 | *group_element = GROUP_ID(group_info, group_base, i, group_shift); |
||
355 | *group_ret = &group_info[i]; |
||
356 | return &_var_info[vindex]; |
||
357 | } |
||
358 | } |
||
359 | return NULL; |
||
360 | } |
||
361 | |||
362 | // find the info structure for a variable |
||
363 | const struct AP_Param::Info *AP_Param::find_var_info(uint8_t *group_element, |
||
364 | const struct GroupInfo **group_ret, |
||
365 | uint8_t *idx) |
||
366 | { |
||
367 | for (uint8_t i=0; i<_num_vars; i++) { |
||
368 | uint8_t type = PGM_UINT8(&_var_info[i].type); |
||
369 | uintptr_t base = PGM_POINTER(&_var_info[i].ptr); |
||
370 | if (type == AP_PARAM_GROUP) { |
||
371 | const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info); |
||
372 | const struct AP_Param::Info *info; |
||
373 | info = find_var_info_group(group_info, i, 0, 0, group_element, group_ret, idx); |
||
374 | if (info != NULL) { |
||
375 | return info; |
||
376 | } |
||
377 | } else if (base == (uintptr_t)this) { |
||
378 | *group_element = 0; |
||
379 | *group_ret = NULL; |
||
380 | *idx = 0; |
||
381 | return &_var_info[i]; |
||
382 | } else if (type == AP_PARAM_VECTOR3F && |
||
383 | (base+sizeof(float) == (uintptr_t)this || |
||
384 | base+2*sizeof(float) == (uintptr_t)this)) { |
||
385 | // we are inside a Vector3f. Work out which element we are |
||
386 | // referring to. |
||
387 | *idx = (((uintptr_t)this) - base)/sizeof(float); |
||
388 | *group_element = 0; |
||
389 | *group_ret = NULL; |
||
390 | return &_var_info[i]; |
||
391 | } |
||
392 | } |
||
393 | return NULL; |
||
394 | } |
||
395 | |||
396 | // return the storage size for a AP_PARAM_* type |
||
397 | const uint8_t AP_Param::type_size(enum ap_var_type type) |
||
398 | { |
||
399 | switch (type) { |
||
400 | case AP_PARAM_NONE: |
||
401 | case AP_PARAM_GROUP: |
||
402 | return 0; |
||
403 | case AP_PARAM_INT8: |
||
404 | return 1; |
||
405 | case AP_PARAM_INT16: |
||
406 | return 2; |
||
407 | case AP_PARAM_INT32: |
||
408 | return 4; |
||
409 | case AP_PARAM_FLOAT: |
||
410 | return 4; |
||
411 | case AP_PARAM_VECTOR3F: |
||
412 | return 3*4; |
||
413 | case AP_PARAM_VECTOR6F: |
||
414 | return 6*4; |
||
415 | case AP_PARAM_MATRIX3F: |
||
416 | return 3*3*4; |
||
417 | } |
||
418 | serialDebug("unknown type %u\n", type); |
||
419 | return 0; |
||
420 | } |
||
421 | |||
422 | // scan the EEPROM looking for a given variable by header content |
||
423 | // return true if found, along with the offset in the EEPROM where |
||
424 | // the variable is stored |
||
425 | // if not found return the offset of the sentinal, or |
||
426 | bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs) |
||
427 | { |
||
428 | struct Param_header phdr; |
||
429 | uint16_t ofs = sizeof(AP_Param::EEPROM_header); |
||
430 | while (ofs < _eeprom_size) { |
||
431 | eeprom_read_block(&phdr, (void *)ofs, sizeof(phdr)); |
||
432 | if (phdr.type == target->type && |
||
433 | phdr.key == target->key && |
||
434 | phdr.group_element == target->group_element) { |
||
435 | // found it |
||
436 | *pofs = ofs; |
||
437 | return true; |
||
438 | } |
||
439 | // note that this is an ||, not an &&, as this makes us more |
||
440 | // robust to power off while adding a variable to EEPROM |
||
441 | if (phdr.type == _sentinal_type || |
||
442 | phdr.key == _sentinal_key || |
||
443 | phdr.group_element == _sentinal_group) { |
||
444 | // we've reached the sentinal |
||
445 | *pofs = ofs; |
||
446 | return false; |
||
447 | } |
||
448 | ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr); |
||
449 | } |
||
450 | *pofs = ~0; |
||
451 | serialDebug("scan past end of eeprom"); |
||
452 | return false; |
||
453 | } |
||
454 | |||
455 | // add a X,Y,Z suffix to the name of a Vector3f element |
||
456 | void AP_Param::add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx) |
||
457 | { |
||
458 | uint8_t len = strnlen(buffer, buffer_size); |
||
459 | if ((size_t)(len+3) >= buffer_size) { |
||
460 | // the suffix doesn't fit |
||
461 | return; |
||
462 | } |
||
463 | buffer[len] = '_'; |
||
464 | if (idx == 0) { |
||
465 | buffer[len+1] = 'X'; |
||
466 | } else if (idx == 1) { |
||
467 | buffer[len+1] = 'Y'; |
||
468 | } else if (idx == 2) { |
||
469 | buffer[len+1] = 'Z'; |
||
470 | } |
||
471 | buffer[len+2] = 0; |
||
472 | } |
||
473 | |||
474 | // Copy the variable's whole name to the supplied buffer. |
||
475 | // |
||
476 | // If the variable is a group member, prepend the group name. |
||
477 | // |
||
478 | void AP_Param::copy_name(char *buffer, size_t buffer_size, bool force_scalar) |
||
479 | { |
||
480 | uint8_t group_element; |
||
481 | const struct GroupInfo *ginfo; |
||
482 | uint8_t idx; |
||
483 | const struct AP_Param::Info *info = find_var_info(&group_element, &ginfo, &idx); |
||
484 | if (info == NULL) { |
||
485 | *buffer = 0; |
||
486 | serialDebug("no info found"); |
||
487 | return; |
||
488 | } |
||
489 | strncpy_P(buffer, info->name, buffer_size); |
||
490 | if (ginfo != NULL) { |
||
491 | uint8_t len = strnlen(buffer, buffer_size); |
||
492 | if (len < buffer_size) { |
||
493 | strncpy_P(&buffer[len], ginfo->name, buffer_size-len); |
||
494 | } |
||
495 | if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == PGM_UINT8(&ginfo->type)) { |
||
496 | // the caller wants a specific element in a Vector3f |
||
497 | add_vector3f_suffix(buffer, buffer_size, idx); |
||
498 | } |
||
499 | } else if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == PGM_UINT8(&info->type)) { |
||
500 | add_vector3f_suffix(buffer, buffer_size, idx); |
||
501 | } |
||
502 | } |
||
503 | |||
504 | // Find a variable by name in a group |
||
505 | AP_Param * |
||
506 | AP_Param::find_group(const char *name, uint8_t vindex, const struct GroupInfo *group_info, enum ap_var_type *ptype) |
||
507 | { |
||
508 | uint8_t type; |
||
509 | for (uint8_t i=0; |
||
510 | (type=PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; |
||
511 | i++) { |
||
512 | #ifdef AP_NESTED_GROUPS_ENABLED |
||
513 | if (type == AP_PARAM_GROUP) { |
||
514 | const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info); |
||
515 | AP_Param *ap = find_group(name, vindex, ginfo, ptype); |
||
516 | if (ap != NULL) { |
||
517 | return ap; |
||
518 | } |
||
519 | } else |
||
520 | #endif // AP_NESTED_GROUPS_ENABLED |
||
521 | if (strcasecmp_P(name, group_info[i].name) == 0) { |
||
522 | uintptr_t p = PGM_POINTER(&_var_info[vindex].ptr); |
||
523 | *ptype = (enum ap_var_type)type; |
||
524 | return (AP_Param *)(p + PGM_POINTER(&group_info[i].offset)); |
||
525 | } else if (type == AP_PARAM_VECTOR3F) { |
||
526 | // special case for finding Vector3f elements |
||
527 | uint8_t suffix_len = strlen_P(group_info[i].name); |
||
528 | if (strncmp_P(name, group_info[i].name, suffix_len) == 0 && |
||
529 | name[suffix_len] == '_' && |
||
530 | name[suffix_len+1] != 0 && |
||
531 | name[suffix_len+2] == 0) { |
||
532 | uintptr_t p = PGM_POINTER(&_var_info[vindex].ptr); |
||
533 | AP_Float *v = (AP_Float *)(p + PGM_POINTER(&group_info[i].offset)); |
||
534 | *ptype = AP_PARAM_FLOAT; |
||
535 | switch (name[suffix_len+1]) { |
||
536 | case 'X': |
||
537 | return (AP_Float *)&v[0]; |
||
538 | case 'Y': |
||
539 | return (AP_Float *)&v[1]; |
||
540 | case 'Z': |
||
541 | return (AP_Float *)&v[2]; |
||
542 | } |
||
543 | } |
||
544 | } |
||
545 | } |
||
546 | return NULL; |
||
547 | } |
||
548 | |||
549 | |||
550 | // Find a variable by name. |
||
551 | // |
||
552 | AP_Param * |
||
553 | AP_Param::find(const char *name, enum ap_var_type *ptype) |
||
554 | { |
||
555 | for (uint8_t i=0; i<_num_vars; i++) { |
||
556 | uint8_t type = PGM_UINT8(&_var_info[i].type); |
||
557 | if (type == AP_PARAM_GROUP) { |
||
558 | uint8_t len = strnlen_P(_var_info[i].name, AP_MAX_NAME_SIZE); |
||
559 | if (strncmp_P(name, _var_info[i].name, len) != 0) { |
||
560 | continue; |
||
561 | } |
||
562 | const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info); |
||
563 | AP_Param *ap = find_group(name + len, i, group_info, ptype); |
||
564 | if (ap != NULL) { |
||
565 | return ap; |
||
566 | } |
||
567 | // we continue looking as we want to allow top level |
||
568 | // parameter to have the same prefix name as group |
||
569 | // parameters, for example CAM_P_G |
||
570 | } else if (strcasecmp_P(name, _var_info[i].name) == 0) { |
||
571 | *ptype = (enum ap_var_type)type; |
||
572 | return (AP_Param *)PGM_POINTER(&_var_info[i].ptr); |
||
573 | } |
||
574 | } |
||
575 | return NULL; |
||
576 | } |
||
577 | |||
578 | // Save the variable to EEPROM, if supported |
||
579 | // |
||
580 | bool AP_Param::save(void) |
||
581 | { |
||
582 | uint8_t group_element = 0; |
||
583 | const struct GroupInfo *ginfo; |
||
584 | uint8_t idx; |
||
585 | const struct AP_Param::Info *info = find_var_info(&group_element, &ginfo, &idx); |
||
586 | const AP_Param *ap; |
||
587 | |||
588 | if (info == NULL) { |
||
589 | // we don't have any info on how to store it |
||
590 | return false; |
||
591 | } |
||
592 | |||
593 | struct Param_header phdr; |
||
594 | |||
595 | // create the header we will use to store the variable |
||
596 | if (ginfo != NULL) { |
||
597 | phdr.type = PGM_UINT8(&ginfo->type); |
||
598 | } else { |
||
599 | phdr.type = PGM_UINT8(&info->type); |
||
600 | } |
||
601 | phdr.key = PGM_UINT8(&info->key); |
||
602 | phdr.group_element = group_element; |
||
603 | |||
604 | ap = this; |
||
605 | if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) { |
||
606 | // only vector3f can have non-zero idx for now |
||
607 | return false; |
||
608 | } |
||
609 | if (idx != 0) { |
||
610 | ap = (const AP_Param *)((uintptr_t)ap) - (idx*sizeof(float)); |
||
611 | } |
||
612 | |||
613 | // scan EEPROM to find the right location |
||
614 | uint16_t ofs; |
||
615 | if (scan(&phdr, &ofs)) { |
||
616 | // found an existing copy of the variable |
||
617 | eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type)); |
||
618 | return true; |
||
619 | } |
||
620 | if (ofs == (uint16_t)~0) { |
||
621 | return false; |
||
622 | } |
||
623 | |||
624 | // write a new sentinal, then the data, then the header |
||
625 | write_sentinal(ofs + sizeof(phdr) + type_size((enum ap_var_type)phdr.type)); |
||
626 | eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type)); |
||
627 | eeprom_write_check(&phdr, ofs, sizeof(phdr)); |
||
628 | return true; |
||
629 | } |
||
630 | |||
631 | // Load the variable from EEPROM, if supported |
||
632 | // |
||
633 | bool AP_Param::load(void) |
||
634 | { |
||
635 | uint8_t group_element = 0; |
||
636 | const struct GroupInfo *ginfo; |
||
637 | uint8_t idx; |
||
638 | const struct AP_Param::Info *info = find_var_info(&group_element, &ginfo, &idx); |
||
639 | if (info == NULL) { |
||
640 | // we don't have any info on how to load it |
||
641 | return false; |
||
642 | } |
||
643 | |||
644 | struct Param_header phdr; |
||
645 | |||
646 | // create the header we will use to match the variable |
||
647 | if (ginfo != NULL) { |
||
648 | phdr.type = PGM_UINT8(&ginfo->type); |
||
649 | } else { |
||
650 | phdr.type = PGM_UINT8(&info->type); |
||
651 | } |
||
652 | phdr.key = PGM_UINT8(&info->key); |
||
653 | phdr.group_element = group_element; |
||
654 | |||
655 | // scan EEPROM to find the right location |
||
656 | uint16_t ofs; |
||
657 | if (!scan(&phdr, &ofs)) { |
||
658 | return false; |
||
659 | } |
||
660 | |||
661 | if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) { |
||
662 | // only vector3f can have non-zero idx for now |
||
663 | return false; |
||
664 | } |
||
665 | |||
666 | AP_Param *ap; |
||
667 | ap = this; |
||
668 | if (idx != 0) { |
||
669 | ap = (AP_Param *)((uintptr_t)ap) - (idx*sizeof(float)); |
||
670 | } |
||
671 | |||
672 | // found it |
||
673 | eeprom_read_block(ap, (void*)(ofs+sizeof(phdr)), type_size((enum ap_var_type)phdr.type)); |
||
674 | return true; |
||
675 | } |
||
676 | |||
677 | // Load all variables from EEPROM |
||
678 | // |
||
679 | bool AP_Param::load_all(void) |
||
680 | { |
||
681 | struct Param_header phdr; |
||
682 | uint16_t ofs = sizeof(AP_Param::EEPROM_header); |
||
683 | while (ofs < _eeprom_size) { |
||
684 | eeprom_read_block(&phdr, (void *)ofs, sizeof(phdr)); |
||
685 | // note that this is an || not an && for robustness |
||
686 | // against power off while adding a variable |
||
687 | if (phdr.type == _sentinal_type || |
||
688 | phdr.key == _sentinal_key || |
||
689 | phdr.group_element == _sentinal_group) { |
||
690 | // we've reached the sentinal |
||
691 | return true; |
||
692 | } |
||
693 | |||
694 | const struct AP_Param::Info *info; |
||
695 | void *ptr; |
||
696 | |||
697 | info = find_by_header(phdr, &ptr); |
||
698 | if (info != NULL) { |
||
699 | eeprom_read_block(ptr, (void*)(ofs+sizeof(phdr)), type_size((enum ap_var_type)phdr.type)); |
||
700 | } |
||
701 | |||
702 | ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr); |
||
703 | } |
||
704 | |||
705 | // we didn't find the sentinal |
||
706 | serialDebug("no sentinal in load_all"); |
||
707 | return false; |
||
708 | } |
||
709 | |||
710 | |||
711 | // return the first variable in _var_info |
||
712 | AP_Param *AP_Param::first(ParamToken *token, enum ap_var_type *ptype) |
||
713 | { |
||
714 | token->key = 0; |
||
715 | token->group_element = 0; |
||
716 | token->idx = 0; |
||
717 | if (_num_vars == 0) { |
||
718 | return NULL; |
||
719 | } |
||
720 | if (ptype != NULL) { |
||
721 | *ptype = (enum ap_var_type)PGM_UINT8(&_var_info[0].type); |
||
722 | } |
||
723 | return (AP_Param *)(PGM_POINTER(&_var_info[0].ptr)); |
||
724 | } |
||
725 | |||
726 | /// Returns the next variable in a group, recursing into groups |
||
727 | /// as needed |
||
728 | AP_Param *AP_Param::next_group(uint8_t vindex, const struct GroupInfo *group_info, |
||
729 | bool *found_current, |
||
730 | uint8_t group_base, |
||
731 | uint8_t group_shift, |
||
732 | ParamToken *token, |
||
733 | enum ap_var_type *ptype) |
||
734 | { |
||
735 | enum ap_var_type type; |
||
736 | for (uint8_t i=0; |
||
737 | (type=(enum ap_var_type)PGM_UINT8(&group_info[i].type)) != AP_PARAM_NONE; |
||
738 | i++) { |
||
739 | #ifdef AP_NESTED_GROUPS_ENABLED |
||
740 | if (type == AP_PARAM_GROUP) { |
||
741 | // a nested group |
||
742 | const struct GroupInfo *ginfo = (const struct GroupInfo *)PGM_POINTER(&group_info[i].group_info); |
||
743 | AP_Param *ap; |
||
744 | ap = next_group(vindex, ginfo, found_current, GROUP_ID(group_info, group_base, i, group_shift), |
||
745 | group_shift + _group_level_shift, token, ptype); |
||
746 | if (ap != NULL) { |
||
747 | return ap; |
||
748 | } |
||
749 | } else |
||
750 | #endif // AP_NESTED_GROUPS_ENABLED |
||
751 | { |
||
752 | if (*found_current) { |
||
753 | // got a new one |
||
754 | token->key = vindex; |
||
755 | token->group_element = GROUP_ID(group_info, group_base, i, group_shift); |
||
756 | token->idx = 0; |
||
757 | if (ptype != NULL) { |
||
758 | *ptype = type; |
||
759 | } |
||
760 | return (AP_Param*)(PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset)); |
||
761 | } |
||
762 | if (GROUP_ID(group_info, group_base, i, group_shift) == token->group_element) { |
||
763 | *found_current = true; |
||
764 | if (type == AP_PARAM_VECTOR3F && token->idx < 3) { |
||
765 | // return the next element of the vector as a |
||
766 | // float |
||
767 | token->idx++; |
||
768 | if (ptype != NULL) { |
||
769 | *ptype = AP_PARAM_FLOAT; |
||
770 | } |
||
771 | uintptr_t ofs = (uintptr_t)PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset); |
||
772 | ofs += sizeof(float)*(token->idx-1); |
||
773 | return (AP_Param *)ofs; |
||
774 | } |
||
775 | } |
||
776 | } |
||
777 | } |
||
778 | return NULL; |
||
779 | } |
||
780 | |||
781 | /// Returns the next variable in _var_info, recursing into groups |
||
782 | /// as needed |
||
783 | AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype) |
||
784 | { |
||
785 | uint8_t i = token->key; |
||
786 | bool found_current = false; |
||
787 | if (i >= _num_vars) { |
||
788 | // illegal token |
||
789 | return NULL; |
||
790 | } |
||
791 | enum ap_var_type type = (enum ap_var_type)PGM_UINT8(&_var_info[i].type); |
||
792 | |||
793 | // allow Vector3f to be seen as 3 variables. First as a vector, |
||
794 | // then as 3 separate floats |
||
795 | if (type == AP_PARAM_VECTOR3F && token->idx < 3) { |
||
796 | token->idx++; |
||
797 | if (ptype != NULL) { |
||
798 | *ptype = AP_PARAM_FLOAT; |
||
799 | } |
||
800 | return (AP_Param *)(((token->idx-1)*sizeof(float))+(uintptr_t)PGM_POINTER(&_var_info[i].ptr)); |
||
801 | } |
||
802 | |||
803 | if (type != AP_PARAM_GROUP) { |
||
804 | i++; |
||
805 | found_current = true; |
||
806 | } |
||
807 | for (; i<_num_vars; i++) { |
||
808 | type = (enum ap_var_type)PGM_UINT8(&_var_info[i].type); |
||
809 | if (type == AP_PARAM_GROUP) { |
||
810 | const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info); |
||
811 | AP_Param *ap = next_group(i, group_info, &found_current, 0, 0, token, ptype); |
||
812 | if (ap != NULL) { |
||
813 | return ap; |
||
814 | } |
||
815 | } else { |
||
816 | // found the next one |
||
817 | token->key = i; |
||
818 | token->group_element = 0; |
||
819 | token->idx = 0; |
||
820 | if (ptype != NULL) { |
||
821 | *ptype = type; |
||
822 | } |
||
823 | return (AP_Param *)(PGM_POINTER(&_var_info[i].ptr)); |
||
824 | } |
||
825 | } |
||
826 | return NULL; |
||
827 | } |
||
828 | |||
829 | /// Returns the next scalar in _var_info, recursing into groups |
||
830 | /// as needed |
||
831 | AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype) |
||
832 | { |
||
833 | AP_Param *ap; |
||
834 | enum ap_var_type type; |
||
835 | while ((ap = next(token, &type)) != NULL && type > AP_PARAM_FLOAT) ; |
||
836 | if (ap != NULL && ptype != NULL) { |
||
837 | *ptype = type; |
||
838 | } |
||
839 | return ap; |
||
840 | } |
||
841 | |||
842 | |||
843 | /// cast a variable to a float given its type |
||
844 | float AP_Param::cast_to_float(enum ap_var_type type) |
||
845 | { |
||
846 | switch (type) { |
||
847 | case AP_PARAM_INT8: |
||
848 | return ((AP_Int8 *)this)->cast_to_float(); |
||
849 | case AP_PARAM_INT16: |
||
850 | return ((AP_Int16 *)this)->cast_to_float(); |
||
851 | case AP_PARAM_INT32: |
||
852 | return ((AP_Int32 *)this)->cast_to_float(); |
||
853 | case AP_PARAM_FLOAT: |
||
854 | return ((AP_Float *)this)->cast_to_float(); |
||
855 | default: |
||
856 | return NAN; |
||
857 | } |
||
858 | } |
||
859 | |||
860 | |||
861 | // print the value of all variables |
||
862 | void AP_Param::show_all(void) |
||
863 | { |
||
864 | ParamToken token; |
||
865 | AP_Param *ap; |
||
866 | enum ap_var_type type; |
||
867 | |||
868 | for (ap=AP_Param::first(&token, &type); |
||
869 | ap; |
||
870 | ap=AP_Param::next_scalar(&token, &type)) { |
||
871 | char s[AP_MAX_NAME_SIZE+1]; |
||
872 | ap->copy_name(s, sizeof(s), true); |
||
873 | s[AP_MAX_NAME_SIZE] = 0; |
||
874 | |||
875 | switch (type) { |
||
876 | case AP_PARAM_INT8: |
||
877 | Serial.printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int8 *)ap)->get()); |
||
878 | break; |
||
879 | case AP_PARAM_INT16: |
||
880 | Serial.printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int16 *)ap)->get()); |
||
881 | break; |
||
882 | case AP_PARAM_INT32: |
||
883 | Serial.printf_P(PSTR("%s: %ld\n"), s, (long)((AP_Int32 *)ap)->get()); |
||
884 | break; |
||
885 | case AP_PARAM_FLOAT: |
||
886 | Serial.printf_P(PSTR("%s: %f\n"), s, ((AP_Float *)ap)->get()); |
||
887 | break; |
||
888 | default: |
||
889 | break; |
||
890 | } |
||
891 | } |
||
892 | } |