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 | /// @file AP_Param.h |
||
10 | /// @brief A system for managing and storing variables that are of |
||
11 | /// general interest to the system. |
||
12 | |||
13 | #ifndef AP_PARAM_H |
||
14 | #define AP_PARAM_H |
||
15 | #include <stddef.h> |
||
16 | #include <string.h> |
||
17 | #include <stdint.h> |
||
18 | |||
19 | #include <avr/pgmspace.h> |
||
20 | #include <avr/eeprom.h> |
||
21 | |||
22 | #define AP_MAX_NAME_SIZE 15 |
||
23 | #define AP_NESTED_GROUPS_ENABLED |
||
24 | |||
25 | // a variant of offsetof() to work around C++ restrictions. |
||
26 | // this can only be used when the offset of a variable in a object |
||
27 | // is constant and known at compile time |
||
28 | #define AP_VAROFFSET(type, element) (((uintptr_t)(&((const type *)1)->element))-1) |
||
29 | |||
30 | // find the type of a variable given the class and element |
||
31 | #define AP_CLASSTYPE(class, element) (((const class *)1)->element.vtype) |
||
32 | |||
33 | // declare a group var_info line |
||
34 | #define AP_GROUPINFO(name, idx, class, element) { AP_CLASSTYPE(class, element), idx, name, AP_VAROFFSET(class, element) } |
||
35 | |||
36 | // declare a nested group entry in a group var_info |
||
37 | #ifdef AP_NESTED_GROUPS_ENABLED |
||
38 | #define AP_NESTEDGROUPINFO(class, idx) { AP_PARAM_GROUP, idx, "", 0, class::var_info } |
||
39 | #endif |
||
40 | |||
41 | #define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "" } |
||
42 | |||
43 | enum ap_var_type { |
||
44 | AP_PARAM_NONE = 0, |
||
45 | AP_PARAM_INT8, |
||
46 | AP_PARAM_INT16, |
||
47 | AP_PARAM_INT32, |
||
48 | AP_PARAM_FLOAT, |
||
49 | AP_PARAM_VECTOR3F, |
||
50 | AP_PARAM_VECTOR6F, |
||
51 | AP_PARAM_MATRIX3F, |
||
52 | AP_PARAM_GROUP |
||
53 | }; |
||
54 | |||
55 | /// Base class for variables. |
||
56 | /// |
||
57 | /// Provides naming and lookup services for variables. |
||
58 | /// |
||
59 | class AP_Param |
||
60 | { |
||
61 | public: |
||
62 | // the Info and GroupInfo structures are passed by the main |
||
63 | // program in setup() to give information on how variables are |
||
64 | // named and their location in memory |
||
65 | struct GroupInfo { |
||
66 | uint8_t type; // AP_PARAM_* |
||
67 | uint8_t idx; // identifier within the group |
||
68 | const char name[AP_MAX_NAME_SIZE]; |
||
69 | uintptr_t offset; // offset within the object |
||
70 | const struct GroupInfo *group_info; |
||
71 | }; |
||
72 | struct Info { |
||
73 | uint8_t type; // AP_PARAM_* |
||
74 | const char name[AP_MAX_NAME_SIZE]; |
||
75 | uint8_t key; // k_param_* |
||
76 | void *ptr; // pointer to the variable in memory |
||
77 | const struct GroupInfo *group_info; |
||
78 | }; |
||
79 | |||
80 | // a token used for first()/next() state |
||
81 | typedef struct { |
||
82 | uint8_t key; |
||
83 | uint8_t group_element; |
||
84 | uint8_t idx; // offset into array types |
||
85 | } ParamToken; |
||
86 | |||
87 | // called once at startup to setup the _var_info[] table. This |
||
88 | // will also check the EEPROM header and re-initialise it if the |
||
89 | // wrong version is found |
||
90 | static bool setup(const struct Info *info, uint8_t num_vars, uint16_t eeprom_size); |
||
91 | |||
92 | // return true if AP_Param has been initialised via setup() |
||
93 | static bool initialised(void); |
||
94 | |||
95 | /// Copy the variable's name, prefixed by any containing group name, to a buffer. |
||
96 | /// |
||
97 | /// If the variable has no name, the buffer will contain an empty string. |
||
98 | /// |
||
99 | /// Note that if the combination of names is larger than the buffer, the |
||
100 | /// result in the buffer will be truncated. |
||
101 | /// |
||
102 | /// @param buffer The destination buffer |
||
103 | /// @param bufferSize Total size of the destination buffer. |
||
104 | /// |
||
105 | void copy_name(char *buffer, size_t bufferSize, bool force_scalar=false); |
||
106 | |||
107 | /// Find a variable by name. |
||
108 | /// |
||
109 | /// If the variable has no name, it cannot be found by this interface. |
||
110 | /// |
||
111 | /// @param name The full name of the variable to be found. |
||
112 | /// @return A pointer to the variable, or NULL if |
||
113 | /// it does not exist. |
||
114 | /// |
||
115 | static AP_Param *find(const char *name, enum ap_var_type *ptype); |
||
116 | |||
117 | /// Save the current value of the variable to EEPROM. |
||
118 | /// |
||
119 | /// @return True if the variable was saved successfully. |
||
120 | /// |
||
121 | bool save(void); |
||
122 | |||
123 | /// Load the variable from EEPROM. |
||
124 | /// |
||
125 | /// @return True if the variable was loaded successfully. |
||
126 | /// |
||
127 | bool load(void); |
||
128 | |||
129 | /// Load all variables from EEPROM |
||
130 | /// |
||
131 | /// This function performs a best-efforts attempt to load all |
||
132 | /// of the variables from EEPROM. If some fail to load, their |
||
133 | /// values will remain as they are. |
||
134 | /// |
||
135 | /// @return False if any variable failed to load |
||
136 | /// |
||
137 | static bool load_all(void); |
||
138 | |||
139 | /// Erase all variables in EEPROM. |
||
140 | /// |
||
141 | static void erase_all(void); |
||
142 | |||
143 | /// print the value of all variables |
||
144 | static void show_all(void); |
||
145 | |||
146 | /// Returns the first variable |
||
147 | /// |
||
148 | /// @return The first variable in _var_info, or NULL if |
||
149 | /// there are none. |
||
150 | /// |
||
151 | static AP_Param *first(ParamToken *token, enum ap_var_type *ptype); |
||
152 | |||
153 | /// Returns the next variable in _var_info, recursing into groups |
||
154 | /// as needed |
||
155 | static AP_Param *next(ParamToken *token, enum ap_var_type *ptype); |
||
156 | |||
157 | /// Returns the next scalar variable in _var_info, recursing into groups |
||
158 | /// as needed |
||
159 | static AP_Param *next_scalar(ParamToken *token, enum ap_var_type *ptype); |
||
160 | |||
161 | /// cast a variable to a float given its type |
||
162 | float cast_to_float(enum ap_var_type type); |
||
163 | |||
164 | private: |
||
165 | /// EEPROM header |
||
166 | /// |
||
167 | /// This structure is placed at the head of the EEPROM to indicate |
||
168 | /// that the ROM is formatted for AP_Param. |
||
169 | /// |
||
170 | struct EEPROM_header { |
||
171 | uint8_t magic[2]; |
||
172 | uint8_t revision; |
||
173 | uint8_t spare; |
||
174 | }; |
||
175 | |||
176 | // This header is prepended to a variable stored in EEPROM. |
||
177 | struct Param_header { |
||
178 | uint8_t key; |
||
179 | uint8_t group_element; |
||
180 | uint8_t type; |
||
181 | }; |
||
182 | |||
183 | // number of bits in each level of nesting of groups |
||
184 | static const uint8_t _group_level_shift = 4; |
||
185 | static const uint8_t _group_bits = 8; |
||
186 | |||
187 | static const uint8_t _sentinal_key = 0xFF; |
||
188 | static const uint8_t _sentinal_type = 0xFF; |
||
189 | static const uint8_t _sentinal_group = 0xFF; |
||
190 | |||
191 | static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits); |
||
192 | static bool duplicate_key(uint8_t vindex, uint8_t key); |
||
193 | static bool check_var_info(void); |
||
194 | const struct Info *find_var_info_group(const struct GroupInfo *group_info, |
||
195 | uint8_t vindex, |
||
196 | uint8_t group_base, |
||
197 | uint8_t group_shift, |
||
198 | uint8_t *group_element, |
||
199 | const struct GroupInfo **group_ret, |
||
200 | uint8_t *idx); |
||
201 | const struct Info *find_var_info(uint8_t *group_element, |
||
202 | const struct GroupInfo **group_ret, |
||
203 | uint8_t *idx); |
||
204 | static const struct Info *find_by_header_group(struct Param_header phdr, void **ptr, |
||
205 | uint8_t vindex, |
||
206 | const struct GroupInfo *group_info, |
||
207 | uint8_t group_base, |
||
208 | uint8_t group_shift); |
||
209 | static const struct Info *find_by_header(struct Param_header phdr, void **ptr); |
||
210 | void add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx); |
||
211 | static AP_Param *find_group(const char *name, uint8_t vindex, const struct GroupInfo *group_info, enum ap_var_type *ptype); |
||
212 | static void write_sentinal(uint16_t ofs); |
||
213 | bool scan(const struct Param_header *phdr, uint16_t *pofs); |
||
214 | static const uint8_t type_size(enum ap_var_type type); |
||
215 | static void eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size); |
||
216 | static AP_Param *next_group(uint8_t vindex, const struct GroupInfo *group_info, |
||
217 | bool *found_current, |
||
218 | uint8_t group_base, |
||
219 | uint8_t group_shift, |
||
220 | ParamToken *token, |
||
221 | enum ap_var_type *ptype); |
||
222 | |||
223 | static uint16_t _eeprom_size; |
||
224 | static uint8_t _num_vars; |
||
225 | static const struct Info *_var_info; |
||
226 | |||
227 | // values filled into the EEPROM header |
||
228 | static const uint8_t k_EEPROM_magic0 = 0x50; |
||
229 | static const uint8_t k_EEPROM_magic1 = 0x41; ///< "AP" |
||
230 | static const uint8_t k_EEPROM_revision = 5; ///< current format revision |
||
231 | }; |
||
232 | |||
233 | /// Template class for scalar variables. |
||
234 | /// |
||
235 | /// Objects of this type have a value, and can be treated in many ways as though they |
||
236 | /// were the value. |
||
237 | /// |
||
238 | /// @tparam T The scalar type of the variable |
||
239 | /// @tparam PT The AP_PARAM_* type |
||
240 | /// |
||
241 | template<typename T, ap_var_type PT> |
||
242 | class AP_ParamT : public AP_Param |
||
243 | { |
||
244 | public: |
||
245 | /// Constructor for scalar variable. |
||
246 | /// |
||
247 | /// Initialises a stand-alone variable with optional initial value. |
||
248 | /// |
||
249 | /// @param default_value Value the variable should have at startup. |
||
250 | /// |
||
251 | AP_ParamT<T,PT> (const T initial_value = 0) : |
||
252 | AP_Param(), |
||
253 | _value(initial_value) |
||
254 | { |
||
255 | } |
||
256 | |||
257 | static const ap_var_type vtype = PT; |
||
258 | |||
259 | /// Value getter |
||
260 | /// |
||
261 | T get(void) const { |
||
262 | return _value; |
||
263 | } |
||
264 | |||
265 | /// Value setter |
||
266 | /// |
||
267 | void set(T v) { |
||
268 | _value = v; |
||
269 | } |
||
270 | |||
271 | /// Combined set and save |
||
272 | /// |
||
273 | bool set_and_save(T v) { |
||
274 | set(v); |
||
275 | return save(); |
||
276 | } |
||
277 | |||
278 | /// Combined set and save, but only does the save if the value if |
||
279 | /// different from the current ram value, thus saving us a |
||
280 | /// scan(). This should only be used where we have not set() the |
||
281 | /// value separately, as otherwise the value in EEPROM won't be |
||
282 | /// updated correctly. |
||
283 | bool set_and_save_ifchanged(T v) { |
||
284 | if (v == _value) { |
||
285 | return true; |
||
286 | } |
||
287 | set(v); |
||
288 | return save(); |
||
289 | } |
||
290 | |||
291 | /// Conversion to T returns a reference to the value. |
||
292 | /// |
||
293 | /// This allows the class to be used in many situations where the value would be legal. |
||
294 | /// |
||
295 | operator T &() { |
||
296 | return _value; |
||
297 | } |
||
298 | |||
299 | /// Copy assignment from self does nothing. |
||
300 | /// |
||
301 | AP_ParamT<T,PT>& operator=(AP_ParamT<T,PT>& v) { |
||
302 | return v; |
||
303 | } |
||
304 | |||
305 | /// Copy assignment from T is equivalent to ::set. |
||
306 | /// |
||
307 | AP_ParamT<T,PT>& operator=(T v) { |
||
308 | _value = v; |
||
309 | return *this; |
||
310 | } |
||
311 | |||
312 | /// AP_ParamT types can implement AP_Param::cast_to_float |
||
313 | /// |
||
314 | float cast_to_float(void) { |
||
315 | return (float)_value; |
||
316 | } |
||
317 | |||
318 | protected: |
||
319 | T _value; |
||
320 | }; |
||
321 | |||
322 | |||
323 | /// Template class for non-scalar variables. |
||
324 | /// |
||
325 | /// Objects of this type have a value, and can be treated in many ways as though they |
||
326 | /// were the value. |
||
327 | /// |
||
328 | /// @tparam T The scalar type of the variable |
||
329 | /// @tparam PT AP_PARAM_* type |
||
330 | /// |
||
331 | template<typename T, ap_var_type PT> |
||
332 | class AP_ParamV : public AP_Param |
||
333 | { |
||
334 | public: |
||
335 | static const ap_var_type vtype = PT; |
||
336 | |||
337 | /// Value getter |
||
338 | /// |
||
339 | T get(void) const { |
||
340 | return _value; |
||
341 | } |
||
342 | |||
343 | /// Value setter |
||
344 | /// |
||
345 | void set(T v) { |
||
346 | _value = v; |
||
347 | } |
||
348 | |||
349 | /// Combined set and save |
||
350 | /// |
||
351 | bool set_and_save(T v) { |
||
352 | set(v); |
||
353 | return save(); |
||
354 | } |
||
355 | |||
356 | /// Conversion to T returns a reference to the value. |
||
357 | /// |
||
358 | /// This allows the class to be used in many situations where the value would be legal. |
||
359 | /// |
||
360 | operator T &() { |
||
361 | return _value; |
||
362 | } |
||
363 | |||
364 | /// Copy assignment from self does nothing. |
||
365 | /// |
||
366 | AP_ParamV<T,PT>& operator=(AP_ParamV<T,PT>& v) { |
||
367 | return v; |
||
368 | } |
||
369 | |||
370 | /// Copy assignment from T is equivalent to ::set. |
||
371 | /// |
||
372 | AP_ParamV<T,PT>& operator=(T v) { |
||
373 | _value = v; |
||
374 | return *this; |
||
375 | } |
||
376 | |||
377 | protected: |
||
378 | T _value; |
||
379 | }; |
||
380 | |||
381 | |||
382 | /// Template class for array variables. |
||
383 | /// |
||
384 | /// Objects created using this template behave like arrays of the type T, |
||
385 | /// but are stored like single variables. |
||
386 | /// |
||
387 | /// @tparam T The scalar type of the variable |
||
388 | /// @tparam N number of elements |
||
389 | /// @tparam PT the AP_PARAM_* type |
||
390 | /// |
||
391 | template<typename T, uint8_t N, ap_var_type PT> |
||
392 | class AP_ParamA : public AP_Param |
||
393 | { |
||
394 | public: |
||
395 | static const ap_var_type vtype = PT; |
||
396 | |||
397 | /// Array operator accesses members. |
||
398 | /// |
||
399 | /// @note It would be nice to range-check i here, but then what would we return? |
||
400 | /// |
||
401 | T &operator [](uint8_t i) { |
||
402 | return _value[i]; |
||
403 | } |
||
404 | |||
405 | /// Value getter |
||
406 | /// |
||
407 | /// @note Returns zero for index values out of range. |
||
408 | /// |
||
409 | T get(uint8_t i) const { |
||
410 | if (i < N) { |
||
411 | return _value[i]; |
||
412 | } else { |
||
413 | return (T)0; |
||
414 | } |
||
415 | } |
||
416 | |||
417 | /// Value setter |
||
418 | /// |
||
419 | /// @note Attempts to set an index out of range are discarded. |
||
420 | /// |
||
421 | void set(uint8_t i, T v) { |
||
422 | if (i < N) { |
||
423 | _value[i] = v; |
||
424 | } |
||
425 | } |
||
426 | |||
427 | /// Copy assignment from self does nothing. |
||
428 | /// |
||
429 | AP_ParamA<T,N,PT>& operator=(AP_ParamA<T,N,PT>& v) { |
||
430 | return v; |
||
431 | } |
||
432 | |||
433 | protected: |
||
434 | T _value[N]; |
||
435 | }; |
||
436 | |||
437 | |||
438 | |||
439 | /// Convenience macro for defining instances of the AP_ParamT template. |
||
440 | /// |
||
441 | // declare a scalar type |
||
442 | // _t is the base type |
||
443 | // _suffix is the suffix on the AP_* type name |
||
444 | // _pt is the enum ap_var_type type |
||
445 | #define AP_PARAMDEF(_t, _suffix, _pt) typedef AP_ParamT<_t, _pt> AP_##_suffix; |
||
446 | AP_PARAMDEF(float, Float, AP_PARAM_FLOAT); // defines AP_Float |
||
447 | AP_PARAMDEF(int8_t, Int8, AP_PARAM_INT8); // defines AP_Int8 |
||
448 | AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16); // defines AP_Int16 |
||
449 | AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32); // defines AP_Int32 |
||
450 | |||
451 | // declare an array type |
||
452 | // _t is the base type |
||
453 | // _suffix is the suffix on the AP_* type name |
||
454 | // _size is the size of the array |
||
455 | // _pt is the enum ap_var_type type |
||
456 | #define AP_PARAMDEFA(_t, _suffix, _size, _pt) typedef AP_ParamA<_t, _size, _pt> AP_##_suffix; |
||
457 | AP_PARAMDEFA(float, Vector6f, 6, AP_PARAM_VECTOR6F); |
||
458 | |||
459 | // declare a non-scalar type |
||
460 | // this is used in AP_Math.h |
||
461 | // _t is the base type |
||
462 | // _suffix is the suffix on the AP_* type name |
||
463 | // _pt is the enum ap_var_type type |
||
464 | #define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_##_suffix; |
||
465 | |||
466 | /// Rely on built in casting for other variable types |
||
467 | /// to minimize template creation and save memory |
||
468 | #define AP_Uint8 AP_Int8 |
||
469 | #define AP_Uint16 AP_Int16 |
||
470 | #define AP_Uint32 AP_Int32 |
||
471 | #define AP_Bool AP_Int8 |
||
472 | |||
473 | #endif // AP_PARAM_H |