diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 803ade3529..67fe3c922d 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -388,6 +388,41 @@ const struct AP_Param::Info *AP_Param::find_var_info(uint32_t * return NULL; } + +// find the info structure for a variable +const struct AP_Param::Info *AP_Param::find_var_info_token(const ParamToken *token, + uint32_t * group_element, + const struct GroupInfo ** group_ret, + uint8_t * idx) +{ + uint8_t i = token->key; + uint8_t type = PGM_UINT8(&_var_info[i].type); + uintptr_t base = PGM_POINTER(&_var_info[i].ptr); + if (type == AP_PARAM_GROUP) { + const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info); + const struct AP_Param::Info *info; + info = find_var_info_group(group_info, i, 0, 0, group_element, group_ret, idx); + if (info != NULL) { + return info; + } + } else if (base == (uintptr_t) this) { + *group_element = 0; + *group_ret = NULL; + *idx = 0; + return &_var_info[i]; + } else if (type == AP_PARAM_VECTOR3F && + (base+sizeof(float) == (uintptr_t) this || + base+2*sizeof(float) == (uintptr_t) this)) { + // we are inside a Vector3f. Work out which element we are + // referring to. + *idx = (((uintptr_t) this) - base)/sizeof(float); + *group_element = 0; + *group_ret = NULL; + return &_var_info[i]; + } + return NULL; +} + // return the storage size for a AP_PARAM_* type uint8_t AP_Param::type_size(enum ap_var_type type) { @@ -498,6 +533,36 @@ void AP_Param::copy_name(char *buffer, size_t buffer_size, bool force_scalar) } } +// Copy the variable's whole name to the supplied buffer. +// +// If the variable is a group member, prepend the group name. +// +void AP_Param::copy_name_token(const ParamToken *token, char *buffer, size_t buffer_size, bool force_scalar) +{ + uint32_t group_element; + const struct GroupInfo *ginfo; + uint8_t idx; + const struct AP_Param::Info *info = find_var_info_token(token, &group_element, &ginfo, &idx); + if (info == NULL) { + *buffer = 0; + serialDebug("no info found"); + return; + } + strncpy_P(buffer, info->name, buffer_size); + if (ginfo != NULL) { + uint8_t len = strnlen(buffer, buffer_size); + if (len < buffer_size) { + strncpy_P(&buffer[len], ginfo->name, buffer_size-len); + } + if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == PGM_UINT8(&ginfo->type)) { + // the caller wants a specific element in a Vector3f + add_vector3f_suffix(buffer, buffer_size, idx); + } + } else if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == PGM_UINT8(&info->type)) { + add_vector3f_suffix(buffer, buffer_size, idx); + } +} + // Find a variable by name in a group AP_Param * AP_Param::find_group(const char *name, uint8_t vindex, const struct GroupInfo *group_info, enum ap_var_type *ptype) diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 0463d607f3..1f7674d73e 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -126,6 +126,8 @@ public: /// void copy_name(char *buffer, size_t bufferSize, bool force_scalar=false); + void copy_name_token(const ParamToken *token, char *buffer, size_t bufferSize, bool force_scalar=false); + /// Find a variable by name. /// /// If the variable has no name, it cannot be found by this interface. @@ -263,6 +265,10 @@ private: uint32_t * group_element, const struct GroupInfo ** group_ret, uint8_t * idx); + const struct Info * find_var_info_token(const ParamToken *token, + uint32_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,