AP_Param: added support for frame specific parameters

this allows for libraries that have parameters that are only activated
on particular frame types
This commit is contained in:
Andrew Tridgell 2017-02-08 10:45:20 +11:00
parent c294519925
commit 79b0c856b2
2 changed files with 56 additions and 3 deletions

View File

@ -71,6 +71,8 @@ uint16_t AP_Param::num_param_overrides = 0;
// storage object
StorageAccess AP_Param::_storage(StorageManager::StorageParam);
// flags indicating frame type
uint16_t AP_Param::_frame_type_flags;
// write to EEPROM
void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
@ -127,7 +129,22 @@ uint32_t AP_Param::group_id(const struct GroupInfo *grpinfo, uint32_t base, uint
}
return base + (grpinfo[i].idx<<shift);
}
/*
check if a frame type should be included. A frame is included if
either there are no frame type flags on a parameter or if at least
one of the flags has been set by set_frame_type_flags()
*/
bool AP_Param::check_frame_type(uint16_t flags)
{
uint16_t frame_flags = flags >> AP_PARAM_FRAME_TYPE_SHIFT;
if (frame_flags == 0) {
return true;
}
return (frame_flags & _frame_type_flags) != 0;
}
// validate a group info table
bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info,
uint16_t * total_size,
@ -1316,6 +1333,9 @@ AP_Param *AP_Param::next_group(uint16_t vindex, const struct GroupInfo *group_in
for (uint8_t i=0;
(type=(enum ap_var_type)group_info[i].type) != AP_PARAM_NONE;
i++) {
if (!check_frame_type(group_info[i].flags)) {
continue;
}
if (type == AP_PARAM_GROUP) {
// a nested group
const struct GroupInfo *ginfo = group_info[i].group_info;
@ -1396,6 +1416,9 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype)
found_current = true;
}
for (; i<_num_vars; i++) {
if (!check_frame_type(_var_info[i].flags)) {
continue;
}
type = (enum ap_var_type)_var_info[i].type;
if (type == AP_PARAM_GROUP) {
const struct GroupInfo *group_info = _var_info[i].group_info;

View File

@ -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 @@
// 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:
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:
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:
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:
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);