// 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); } }
void AP_Param::copy_name_info(const struct AP_Param::Info *info, const struct GroupInfo *ginfo, uint8_t idx, char *buffer, size_t buffer_size, bool force_scalar) const { strncpy(buffer, info->name, buffer_size); if (ginfo != NULL) { uint8_t len = strnlen(buffer, buffer_size); if (len < buffer_size) { strncpy(&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); } }