mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
uncrustify libraries/AP_Common/AP_Param.h with fixups by hand
This commit is contained in:
parent
11fb74ee7b
commit
b78c1b21a7
@ -28,18 +28,18 @@
|
||||
#define AP_VAROFFSET(type, element) (((uintptr_t)(&((const type *)1)->element))-1)
|
||||
|
||||
// find the type of a variable given the class and element
|
||||
#define AP_CLASSTYPE(class, element) (((const class *)1)->element.vtype)
|
||||
#define AP_CLASSTYPE(class, element) (((const class *) 1)->element.vtype)
|
||||
|
||||
// declare a group var_info line
|
||||
#define AP_GROUPINFO(name, idx, class, element, def) { AP_CLASSTYPE(class, element), idx, name, AP_VAROFFSET(class, element), {def_value:def} }
|
||||
#define AP_GROUPINFO(name, idx, class, element, def) { AP_CLASSTYPE(class, element), idx, name, AP_VAROFFSET(class, element), {def_value : def} }
|
||||
|
||||
// declare a nested group entry in a group var_info
|
||||
#ifdef AP_NESTED_GROUPS_ENABLED
|
||||
#define AP_NESTEDGROUPINFO(class, idx) { AP_PARAM_GROUP, idx, "", 0, { group_info: class::var_info } }
|
||||
#define AP_NESTEDGROUPINFO(class, idx) { AP_PARAM_GROUP, idx, "", 0, { group_info : class::var_info } }
|
||||
#endif
|
||||
|
||||
#define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : NULL } }
|
||||
#define AP_VAREND { AP_PARAM_NONE, "", 0, NULL, { group_info : NULL } }
|
||||
#define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : NULL } }
|
||||
#define AP_VAREND { AP_PARAM_NONE, "", 0, NULL, { group_info : NULL } }
|
||||
|
||||
enum ap_var_type {
|
||||
AP_PARAM_NONE = 0,
|
||||
@ -87,7 +87,7 @@ public:
|
||||
// called once at startup to setup the _var_info[] table. This
|
||||
// will also check the EEPROM header and re-initialise it if the
|
||||
// wrong version is found
|
||||
static bool setup(const struct Info *info, uint16_t eeprom_size);
|
||||
static bool setup(const struct Info *info, uint16_t eeprom_size);
|
||||
|
||||
// constructor to load default values and setup var_info table
|
||||
AP_Param(const struct Info *info, uint16_t eeprom_size) {
|
||||
@ -96,19 +96,21 @@ public:
|
||||
}
|
||||
|
||||
// empty constructor for child classes
|
||||
AP_Param() {}
|
||||
AP_Param() {
|
||||
}
|
||||
|
||||
// a token used for first()/next() state
|
||||
typedef struct {
|
||||
uint32_t key:8;
|
||||
uint32_t idx:6; // offset into array types
|
||||
uint32_t group_element:18;
|
||||
uint32_t key : 8;
|
||||
uint32_t idx : 6; // offset into array types
|
||||
uint32_t group_element : 18;
|
||||
} ParamToken;
|
||||
|
||||
// return true if AP_Param has been initialised via setup()
|
||||
static bool initialised(void);
|
||||
|
||||
/// Copy the variable's name, prefixed by any containing group name, to a buffer.
|
||||
/// Copy the variable's name, prefixed by any containing group name, to a
|
||||
/// buffer.
|
||||
///
|
||||
/// If the variable has no name, the buffer will contain an empty string.
|
||||
///
|
||||
@ -128,7 +130,7 @@ public:
|
||||
/// @return A pointer to the variable, or NULL if
|
||||
/// it does not exist.
|
||||
///
|
||||
static AP_Param *find(const char *name, enum ap_var_type *ptype);
|
||||
static AP_Param * find(const char *name, enum ap_var_type *ptype);
|
||||
|
||||
/// Save the current value of the variable to EEPROM.
|
||||
///
|
||||
@ -152,39 +154,39 @@ public:
|
||||
///
|
||||
static bool load_all(void);
|
||||
|
||||
// set a AP_Param variable to a specified value
|
||||
static void set_value(enum ap_var_type type, void *ptr, float def_value);
|
||||
// set a AP_Param variable to a specified value
|
||||
static void set_value(enum ap_var_type type, void *ptr, float def_value);
|
||||
|
||||
// load default values for scalars in a group
|
||||
static void load_defaults_group(const struct GroupInfo *group_info, uintptr_t base);
|
||||
static void load_defaults_group(const struct GroupInfo *group_info, uintptr_t base);
|
||||
|
||||
// load default values for all scalars
|
||||
static void load_defaults(void);
|
||||
static void load_defaults(void);
|
||||
|
||||
/// Erase all variables in EEPROM.
|
||||
///
|
||||
static void erase_all(void);
|
||||
static void erase_all(void);
|
||||
|
||||
/// print the value of all variables
|
||||
static void show_all(void);
|
||||
static void show_all(void);
|
||||
|
||||
/// Returns the first variable
|
||||
///
|
||||
/// @return The first variable in _var_info, or NULL if
|
||||
/// there are none.
|
||||
///
|
||||
static AP_Param *first(ParamToken *token, enum ap_var_type *ptype);
|
||||
static AP_Param * first(ParamToken *token, enum ap_var_type *ptype);
|
||||
|
||||
/// Returns the next variable in _var_info, recursing into groups
|
||||
/// as needed
|
||||
static AP_Param *next(ParamToken *token, enum ap_var_type *ptype);
|
||||
static AP_Param * next(ParamToken *token, enum ap_var_type *ptype);
|
||||
|
||||
/// Returns the next scalar variable in _var_info, recursing into groups
|
||||
/// as needed
|
||||
static AP_Param *next_scalar(ParamToken *token, enum ap_var_type *ptype);
|
||||
static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype);
|
||||
|
||||
/// cast a variable to a float given its type
|
||||
float cast_to_float(enum ap_var_type type);
|
||||
float cast_to_float(enum ap_var_type type);
|
||||
|
||||
private:
|
||||
/// EEPROM header
|
||||
@ -193,77 +195,96 @@ private:
|
||||
/// that the ROM is formatted for AP_Param.
|
||||
///
|
||||
struct EEPROM_header {
|
||||
uint8_t magic[2];
|
||||
uint8_t revision;
|
||||
uint8_t spare;
|
||||
uint8_t magic[2];
|
||||
uint8_t revision;
|
||||
uint8_t spare;
|
||||
};
|
||||
|
||||
/* This header is prepended to a variable stored in EEPROM.
|
||||
The meaning is as follows:
|
||||
|
||||
- key: the k_param enum value from Parameter.h in the sketch
|
||||
|
||||
- group_element: This is zero for top level parameters. For
|
||||
parameters stored within an object this is divided
|
||||
into 3 lots of 6 bits, allowing for three levels
|
||||
of object to be stored in the eeprom
|
||||
|
||||
- type: the ap_var_type value for the variable
|
||||
*/
|
||||
* The meaning is as follows:
|
||||
*
|
||||
* - key: the k_param enum value from Parameter.h in the sketch
|
||||
*
|
||||
* - group_element: This is zero for top level parameters. For
|
||||
* parameters stored within an object this is divided
|
||||
* into 3 lots of 6 bits, allowing for three levels
|
||||
* of object to be stored in the eeprom
|
||||
*
|
||||
* - type: the ap_var_type value for the variable
|
||||
*/
|
||||
struct Param_header {
|
||||
uint32_t key:8;
|
||||
uint32_t type:6;
|
||||
uint32_t group_element:18;
|
||||
uint32_t key : 8;
|
||||
uint32_t type : 6;
|
||||
uint32_t group_element : 18;
|
||||
};
|
||||
|
||||
// number of bits in each level of nesting of groups
|
||||
static const uint8_t _group_level_shift = 6;
|
||||
static const uint8_t _group_bits = 18;
|
||||
static const uint8_t _group_level_shift = 6;
|
||||
static const uint8_t _group_bits = 18;
|
||||
|
||||
static const uint8_t _sentinal_key = 0xFF;
|
||||
static const uint8_t _sentinal_type = 0x3F;
|
||||
static const uint8_t _sentinal_group = 0xFF;
|
||||
static const uint8_t _sentinal_key = 0xFF;
|
||||
static const uint8_t _sentinal_type = 0x3F;
|
||||
static const uint8_t _sentinal_group = 0xFF;
|
||||
|
||||
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits);
|
||||
static bool duplicate_key(uint8_t vindex, uint8_t key);
|
||||
static bool check_var_info(void);
|
||||
const struct Info *find_var_info_group(const struct GroupInfo *group_info,
|
||||
uint8_t vindex,
|
||||
uint8_t group_base,
|
||||
uint8_t group_shift,
|
||||
uint8_t *group_element,
|
||||
const struct GroupInfo **group_ret,
|
||||
uint8_t *idx);
|
||||
const struct Info *find_var_info(uint8_t *group_element,
|
||||
const struct GroupInfo **group_ret,
|
||||
uint8_t *idx);
|
||||
static const struct Info *find_by_header_group(struct Param_header phdr, void **ptr,
|
||||
uint8_t vindex,
|
||||
const struct GroupInfo *group_info,
|
||||
uint8_t group_base,
|
||||
uint8_t group_shift);
|
||||
static const struct Info *find_by_header(struct Param_header phdr, void **ptr);
|
||||
void add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx);
|
||||
static AP_Param *find_group(const char *name, uint8_t vindex, const struct GroupInfo *group_info, enum ap_var_type *ptype);
|
||||
static void write_sentinal(uint16_t ofs);
|
||||
bool scan(const struct Param_header *phdr, uint16_t *pofs);
|
||||
static const uint8_t type_size(enum ap_var_type type);
|
||||
static void eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size);
|
||||
static AP_Param *next_group(uint8_t vindex, const struct GroupInfo *group_info,
|
||||
bool *found_current,
|
||||
uint8_t group_base,
|
||||
uint8_t group_shift,
|
||||
ParamToken *token,
|
||||
enum ap_var_type *ptype);
|
||||
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, uint8_t max_bits);
|
||||
static bool duplicate_key(uint8_t vindex, uint8_t key);
|
||||
static bool check_var_info(void);
|
||||
const struct Info * find_var_info_group(
|
||||
const struct GroupInfo * group_info,
|
||||
uint8_t vindex,
|
||||
uint8_t group_base,
|
||||
uint8_t group_shift,
|
||||
uint8_t * group_element,
|
||||
const struct GroupInfo ** group_ret,
|
||||
uint8_t * idx);
|
||||
const struct Info * find_var_info(
|
||||
uint8_t * group_element,
|
||||
const struct GroupInfo ** group_ret,
|
||||
uint8_t * idx);
|
||||
static const struct Info * find_by_header_group(
|
||||
struct Param_header phdr, void **ptr,
|
||||
uint8_t vindex,
|
||||
const struct GroupInfo *group_info,
|
||||
uint8_t group_base,
|
||||
uint8_t group_shift);
|
||||
static const struct Info * find_by_header(
|
||||
struct Param_header phdr,
|
||||
void **ptr);
|
||||
void add_vector3f_suffix(
|
||||
char *buffer,
|
||||
size_t buffer_size,
|
||||
uint8_t idx);
|
||||
static AP_Param * find_group(
|
||||
const char *name,
|
||||
uint8_t vindex,
|
||||
const struct GroupInfo *group_info,
|
||||
enum ap_var_type *ptype);
|
||||
static void write_sentinal(uint16_t ofs);
|
||||
bool scan(
|
||||
const struct Param_header *phdr,
|
||||
uint16_t *pofs);
|
||||
static const uint8_t type_size(enum ap_var_type type);
|
||||
static void eeprom_write_check(
|
||||
const void *ptr,
|
||||
uint16_t ofs,
|
||||
uint8_t size);
|
||||
static AP_Param * next_group(
|
||||
uint8_t vindex,
|
||||
const struct GroupInfo *group_info,
|
||||
bool *found_current,
|
||||
uint8_t group_base,
|
||||
uint8_t group_shift,
|
||||
ParamToken *token,
|
||||
enum ap_var_type *ptype);
|
||||
|
||||
static uint16_t _eeprom_size;
|
||||
static uint8_t _num_vars;
|
||||
static const struct Info *_var_info;
|
||||
static uint16_t _eeprom_size;
|
||||
static uint8_t _num_vars;
|
||||
static const struct Info * _var_info;
|
||||
|
||||
// values filled into the EEPROM header
|
||||
static const uint8_t k_EEPROM_magic0 = 0x50;
|
||||
static const uint8_t k_EEPROM_magic1 = 0x41; ///< "AP"
|
||||
static const uint8_t k_EEPROM_revision = 6; ///< current format revision
|
||||
static const uint8_t k_EEPROM_magic0 = 0x50;
|
||||
static const uint8_t k_EEPROM_magic1 = 0x41; ///< "AP"
|
||||
static const uint8_t k_EEPROM_revision = 6; ///< current format revision
|
||||
};
|
||||
|
||||
/// Template class for scalar variables.
|
||||
@ -278,7 +299,7 @@ template<typename T, ap_var_type PT>
|
||||
class AP_ParamT : public AP_Param
|
||||
{
|
||||
public:
|
||||
static const ap_var_type vtype = PT;
|
||||
static const ap_var_type vtype = PT;
|
||||
|
||||
/// Value getter
|
||||
///
|
||||
@ -322,13 +343,13 @@ public:
|
||||
|
||||
/// Copy assignment from self does nothing.
|
||||
///
|
||||
AP_ParamT<T,PT>& operator=(AP_ParamT<T,PT>& v) {
|
||||
AP_ParamT<T,PT>& operator= (AP_ParamT<T,PT>& v) {
|
||||
return v;
|
||||
}
|
||||
|
||||
/// Copy assignment from T is equivalent to ::set.
|
||||
///
|
||||
AP_ParamT<T,PT>& operator=(T v) {
|
||||
AP_ParamT<T,PT>& operator= (T v) {
|
||||
_value = v;
|
||||
return *this;
|
||||
}
|
||||
@ -357,23 +378,23 @@ class AP_ParamV : public AP_Param
|
||||
{
|
||||
public:
|
||||
|
||||
static const ap_var_type vtype = PT;
|
||||
static const ap_var_type vtype = PT;
|
||||
|
||||
/// Value getter
|
||||
///
|
||||
T get(void) const {
|
||||
T get(void) const {
|
||||
return _value;
|
||||
}
|
||||
|
||||
/// Value setter
|
||||
///
|
||||
void set(T v) {
|
||||
void set(T v) {
|
||||
_value = v;
|
||||
}
|
||||
|
||||
/// Combined set and save
|
||||
///
|
||||
bool set_and_save(T v) {
|
||||
bool set_and_save(T v) {
|
||||
set(v);
|
||||
return save();
|
||||
}
|
||||
@ -388,19 +409,19 @@ public:
|
||||
|
||||
/// Copy assignment from self does nothing.
|
||||
///
|
||||
AP_ParamV<T,PT>& operator=(AP_ParamV<T,PT>& v) {
|
||||
AP_ParamV<T,PT>& operator =(AP_ParamV<T,PT>& v) {
|
||||
return v;
|
||||
}
|
||||
|
||||
/// Copy assignment from T is equivalent to ::set.
|
||||
///
|
||||
AP_ParamV<T,PT>& operator=(T v) {
|
||||
AP_ParamV<T,PT>& operator =(T v) {
|
||||
_value = v;
|
||||
return *this;
|
||||
}
|
||||
|
||||
protected:
|
||||
T _value;
|
||||
T _value;
|
||||
};
|
||||
|
||||
|
||||
@ -424,7 +445,7 @@ public:
|
||||
///
|
||||
/// @note It would be nice to range-check i here, but then what would we return?
|
||||
///
|
||||
T &operator [](uint8_t i) {
|
||||
T & operator[](uint8_t i) {
|
||||
return _value[i];
|
||||
}
|
||||
|
||||
@ -444,7 +465,7 @@ public:
|
||||
///
|
||||
/// @note Attempts to set an index out of range are discarded.
|
||||
///
|
||||
void set(uint8_t i, T v) {
|
||||
void set(uint8_t i, T v) {
|
||||
if (i < N) {
|
||||
_value[i] = v;
|
||||
}
|
||||
@ -452,7 +473,7 @@ public:
|
||||
|
||||
/// Copy assignment from self does nothing.
|
||||
///
|
||||
AP_ParamA<T,N,PT>& operator=(AP_ParamA<T,N,PT>& v) {
|
||||
AP_ParamA<T,N,PT>& operator= (AP_ParamA<T,N,PT>& v) {
|
||||
return v;
|
||||
}
|
||||
|
||||
@ -468,7 +489,7 @@ protected:
|
||||
// _t is the base type
|
||||
// _suffix is the suffix on the AP_* type name
|
||||
// _pt is the enum ap_var_type type
|
||||
#define AP_PARAMDEF(_t, _suffix, _pt) typedef AP_ParamT<_t, _pt> AP_##_suffix;
|
||||
#define AP_PARAMDEF(_t, _suffix, _pt) typedef AP_ParamT<_t, _pt> AP_ ## _suffix;
|
||||
AP_PARAMDEF(float, Float, AP_PARAM_FLOAT); // defines AP_Float
|
||||
AP_PARAMDEF(int8_t, Int8, AP_PARAM_INT8); // defines AP_Int8
|
||||
AP_PARAMDEF(int16_t, Int16, AP_PARAM_INT16); // defines AP_Int16
|
||||
@ -479,7 +500,7 @@ AP_PARAMDEF(int32_t, Int32, AP_PARAM_INT32); // defines AP_Int32
|
||||
// _suffix is the suffix on the AP_* type name
|
||||
// _size is the size of the array
|
||||
// _pt is the enum ap_var_type type
|
||||
#define AP_PARAMDEFA(_t, _suffix, _size, _pt) typedef AP_ParamA<_t, _size, _pt> AP_##_suffix;
|
||||
#define AP_PARAMDEFA(_t, _suffix, _size, _pt) typedef AP_ParamA<_t, _size, _pt> AP_ ## _suffix;
|
||||
AP_PARAMDEFA(float, Vector6f, 6, AP_PARAM_VECTOR6F);
|
||||
|
||||
// declare a non-scalar type
|
||||
@ -487,7 +508,7 @@ AP_PARAMDEFA(float, Vector6f, 6, AP_PARAM_VECTOR6F);
|
||||
// _t is the base type
|
||||
// _suffix is the suffix on the AP_* type name
|
||||
// _pt is the enum ap_var_type type
|
||||
#define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_##_suffix;
|
||||
#define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_ ## _suffix;
|
||||
|
||||
/// Rely on built in casting for other variable types
|
||||
/// to minimize template creation and save memory
|
||||
|
Loading…
Reference in New Issue
Block a user