|
|
|
@ -49,6 +49,20 @@
@@ -49,6 +49,20 @@
|
|
|
|
|
// no conflict with the parent
|
|
|
|
|
#define AP_PARAM_NO_SHIFT 8 |
|
|
|
|
|
|
|
|
|
// vehicle and frame type flags, used to hide parameters when not
|
|
|
|
|
// relevent to a vehicle type. Use AP_Param::set_frame_type_flags() to
|
|
|
|
|
// enable parameters flagged in this way. frame type flags are stored
|
|
|
|
|
// in flags field, shifted by AP_PARAM_FRAME_TYPE_SHIFT.
|
|
|
|
|
#define AP_PARAM_FRAME_TYPE_SHIFT 4 |
|
|
|
|
|
|
|
|
|
// supported frame types for parameters
|
|
|
|
|
#define AP_PARAM_FRAME_COPTER (1<<0) |
|
|
|
|
#define AP_PARAM_FRAME_ROVER (1<<1) |
|
|
|
|
#define AP_PARAM_FRAME_PLANE (1<<2) |
|
|
|
|
#define AP_PARAM_FRAME_SUB (1<<3) |
|
|
|
|
#define AP_PARAM_FRAME_TRICOPTER (1<<4) |
|
|
|
|
#define AP_PARAM_FRAME_HELI (1<<5) |
|
|
|
|
|
|
|
|
|
// a variant of offsetof() to work around C++ restrictions.
|
|
|
|
|
// this can only be used when the offset of a variable in a object
|
|
|
|
|
// is constant and known at compile time
|
|
|
|
@ -60,6 +74,12 @@
@@ -60,6 +74,12 @@
|
|
|
|
|
// declare a group var_info line
|
|
|
|
|
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags) { AP_CLASSTYPE(clazz, element), idx, name, AP_VAROFFSET(clazz, element), {def_value : def}, flags } |
|
|
|
|
|
|
|
|
|
// declare a group var_info line with a frame type mask
|
|
|
|
|
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, (frame_flags)<<AP_PARAM_FRAME_TYPE_SHIFT ) |
|
|
|
|
|
|
|
|
|
// declare a group var_info line with both flags and frame type mask
|
|
|
|
|
#define AP_GROUPINFO_FLAGS_FRAME(name, idx, clazz, element, def, flags, frame_flags) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags|((frame_flags)<<AP_PARAM_FRAME_TYPE_SHIFT) ) |
|
|
|
|
|
|
|
|
|
// declare a group var_info line
|
|
|
|
|
#define AP_GROUPINFO(name, idx, clazz, element, def) AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, 0) |
|
|
|
|
|
|
|
|
@ -106,7 +126,7 @@ public:
@@ -106,7 +126,7 @@ public:
|
|
|
|
|
const struct GroupInfo *group_info; |
|
|
|
|
const float def_value; |
|
|
|
|
}; |
|
|
|
|
uint8_t flags; |
|
|
|
|
uint16_t flags; |
|
|
|
|
}; |
|
|
|
|
struct Info { |
|
|
|
|
uint8_t type; // AP_PARAM_*
|
|
|
|
@ -117,7 +137,7 @@ public:
@@ -117,7 +137,7 @@ public:
|
|
|
|
|
const struct GroupInfo *group_info; |
|
|
|
|
const float def_value; |
|
|
|
|
}; |
|
|
|
|
uint8_t flags; |
|
|
|
|
uint16_t flags; |
|
|
|
|
}; |
|
|
|
|
struct ConversionInfo { |
|
|
|
|
uint16_t old_key; // k_param_*
|
|
|
|
@ -363,6 +383,14 @@ public:
@@ -363,6 +383,14 @@ public:
|
|
|
|
|
|
|
|
|
|
static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; } |
|
|
|
|
|
|
|
|
|
// set frame type flags. Used to unhide frame specific parameters
|
|
|
|
|
static void set_frame_type_flags(uint16_t flags_to_set) { |
|
|
|
|
_frame_type_flags |= flags_to_set; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check if a given frame type should be included
|
|
|
|
|
static bool check_frame_type(uint16_t flags); |
|
|
|
|
|
|
|
|
|
private: |
|
|
|
|
/// EEPROM header
|
|
|
|
|
///
|
|
|
|
@ -403,6 +431,8 @@ private:
@@ -403,6 +431,8 @@ private:
|
|
|
|
|
static const uint8_t _sentinal_type = 0x1F; |
|
|
|
|
static const uint8_t _sentinal_group = 0xFF; |
|
|
|
|
|
|
|
|
|
static uint16_t _frame_type_flags; |
|
|
|
|
|
|
|
|
|
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,
|
|
|
|
|
uint8_t max_bits, uint8_t prefix_length); |
|
|
|
|
static bool duplicate_key(uint16_t vindex, uint16_t key); |
|
|
|
|