blob: 19f2dddc32f7fa978cee5a2f3753d0007c618a05 [file] [log] [blame]
/*****************************************************************************
* Copyright (c) 2020 CEA LIST.
*
*
* All rights reserved. This program and the accompanying materials
* are made available under the terms of the Eclipse Public License v2.0
* which accompanies this distribution, and is available at
* https://www.eclipse.org/legal/epl-2.0/
*
* Contributors:
* Ansgar Radermacher ansgar.radermacher@cea.fr
*
*****************************************************************************/
package org.eclipse.papyrus.robotics.ros2.reverse.fromfile;
import java.util.ArrayList;
import java.util.HashMap;
import java.util.List;
import java.util.Map;
import org.eclipse.cdt.core.dom.ast.ASTTypeUtil;
import org.eclipse.cdt.core.dom.ast.IASTExpression;
import org.eclipse.cdt.core.dom.ast.IASTFieldReference;
import org.eclipse.cdt.core.dom.ast.IASTFunctionCallExpression;
import org.eclipse.cdt.core.dom.ast.IASTFunctionDefinition;
import org.eclipse.cdt.core.dom.ast.IASTIdExpression;
import org.eclipse.cdt.core.dom.ast.IASTInitializerClause;
import org.eclipse.cdt.core.dom.ast.IASTLiteralExpression;
import org.eclipse.cdt.core.dom.ast.IASTName;
import org.eclipse.cdt.core.dom.ast.IASTNode;
import org.eclipse.cdt.core.dom.ast.IASTTranslationUnit;
import org.eclipse.cdt.core.dom.ast.IASTUnaryExpression;
import org.eclipse.cdt.core.dom.ast.IBinding;
import org.eclipse.cdt.core.dom.ast.IType;
import org.eclipse.cdt.core.dom.ast.IVariable;
import org.eclipse.cdt.core.dom.ast.cpp.ICPPASTNamespaceDefinition;
import org.eclipse.cdt.core.dom.ast.cpp.ICPPBinding;
import org.eclipse.cdt.internal.core.model.ASTStringUtil;
import org.eclipse.emf.common.util.URI;
import org.eclipse.emf.ecore.resource.ResourceSet;
import org.eclipse.papyrus.designer.languages.common.base.StdUriConstants;
import org.eclipse.papyrus.designer.uml.tools.utils.ElementUtils;
import org.eclipse.papyrus.designer.infra.base.StringUtils;
import org.eclipse.papyrus.robotics.core.utils.ParameterUtils;
import org.eclipse.papyrus.robotics.profile.robotics.parameters.ParameterEntry;
import org.eclipse.papyrus.robotics.ros2.reverse.ParamInfo;
import org.eclipse.papyrus.uml.diagram.wizards.Activator;
import org.eclipse.papyrus.uml.tools.utils.PackageUtil;
import org.eclipse.papyrus.uml.tools.utils.StereotypeUtil;
import org.eclipse.uml2.uml.Class;
import org.eclipse.uml2.uml.NamedElement;
import org.eclipse.uml2.uml.Package;
import org.eclipse.uml2.uml.Property;
import org.eclipse.uml2.uml.Type;
public class ReverseParametersFromSource {
private static final String ADD_PARAMETER = "add_parameter"; //$NON-NLS-1$
private static final String GET_PARAMETER = "get_parameter"; //$NON-NLS-1$
private static final String DECLARE_PARAMETER = "declare_parameter"; //$NON-NLS-1$
protected Class component;
protected IASTTranslationUnit ast;
/**
* a parameter info list (in addition to the map below, to
* preserve the order of the entries
*/
protected List<ParamInfo> paramInfos;
protected Map<String, ParamInfo> paramInfoMap;
enum EParam {
ADD_OR_DECLARE, GET_PARAM, NONE
};
public ReverseParametersFromSource(Class component, IASTTranslationUnit ast) {
this.component = component;
this.ast = ast;
paramInfoMap = new HashMap<String, ParamInfo>();
paramInfos = new ArrayList<ParamInfo>();
}
public ParamInfo getParamInfo(String paramName) {
ParamInfo paramInfo = paramInfoMap.get(paramName);
if (paramInfo == null) {
paramInfo = new ParamInfo();
paramInfos.add(paramInfo);
paramInfoMap.put(paramName, paramInfo);
}
return paramInfo;
}
public List<ParamInfo> getParamInfos() {
return paramInfos;
}
public void updateParameters() {
Class paramSet = ParameterUtils.getParameterClass(component);
scanFunctions(ast);
for (ParamInfo pi : paramInfos) {
Property paramUML = paramSet.createOwnedAttribute(pi.name, pi.type);
ParameterEntry entry = StereotypeUtil.applyApp(paramUML, ParameterEntry.class);
if (pi.defaultValue != null) {
paramUML.setDefault(pi.defaultValue);
}
if (pi.description != null) {
entry.setDescription(pi.description);
}
}
}
public void scanFunctions(IASTNode node) {
for (IASTNode child : node.getChildren()) {
if (child instanceof IASTFunctionDefinition) {
IASTFunctionDefinition definition = (IASTFunctionDefinition) child;
scanBody(definition.getBody());
}
if (child instanceof ICPPASTNamespaceDefinition) {
// recurse into namespaces
scanFunctions(child);
}
}
}
public static String getASTName(IASTExpression expr) {
if (expr instanceof IASTFieldReference) {
IASTName fieldName = ((IASTFieldReference) expr).getFieldName();
if (fieldName != null) {
return fieldName.toString();
}
return ""; //$NON-NLS-1$
} else {
return expr.toString();
}
}
public static EParam getProviderFromCall(String fctName) {
if (fctName.equals(DECLARE_PARAMETER)) {
return EParam.ADD_OR_DECLARE;
}
if (fctName.equals(ADD_PARAMETER)) {
return EParam.ADD_OR_DECLARE;
}
if (fctName.equals(GET_PARAMETER)) {
return EParam.GET_PARAM;
}
return EParam.NONE;
}
/**
* This function determines the default value by dereferencing function calls recursively.
* This is required, since default parameters are wrapper by one or calls, as for instance
* in rclcpp::ParameterValue(0.2) or rclcpp::ParameterValue(std::string("base_footprint"))
*
* @param fCallExpr
* an AST function Call
* @return the defaultValue or null
*/
@SuppressWarnings("restriction")
public static String deduceDefaultValue(IASTFunctionCallExpression fCallExpr) {
// check arguments
IASTInitializerClause arguments[] = fCallExpr.getArguments();
if (arguments.length > 0) {
if (arguments[0] instanceof IASTLiteralExpression) {
// direct default value
return StringUtils.unquote(arguments[0].toString());
} else if (arguments[0] instanceof IASTUnaryExpression) {
// typically for negative values
// TODO: is there a better (non-internal) way to get the expression string?
IASTUnaryExpression unaryExpr = (IASTUnaryExpression) arguments[0];
return ASTStringUtil.getExpressionString(unaryExpr);
} else if (arguments[0] instanceof IASTFunctionCallExpression) {
// wrapper by function call
return deduceDefaultValue((IASTFunctionCallExpression) arguments[0]);
}
}
return null;
}
/**
* Obtain default value from declare or add_parameter call
*
* @param fCallExpr
*/
public void obtainDeclOrAddDetails(IASTFunctionCallExpression fCallExpr) {
IASTInitializerClause arguments[] = fCallExpr.getArguments();
String paramName = StringUtils.unquote(arguments[0].toString());
String defaultValue = null;
String description = null;
if (arguments.length > 1) {
// default value
if (arguments[1] instanceof IASTFunctionCallExpression) {
defaultValue = deduceDefaultValue((IASTFunctionCallExpression) arguments[1]);
}
}
if (arguments.length > 2) {
description = StringUtils.unquote(arguments[2].toString());
}
ParamInfo paramInfo = getParamInfo(paramName);
paramInfo.name = paramName;
paramInfo.description = description;
paramInfo.defaultValue = defaultValue;
}
/**
* The type can be obtained from the get_parameter call
*
* @param fCallExpr
*/
@SuppressWarnings("nls")
public void obtainGetDetails(IASTFunctionCallExpression fCallExpr) {
IASTInitializerClause arguments[] = fCallExpr.getArguments();
String paramName = arguments[0].toString().trim();
paramName = StringUtils.unquote(paramName);
String typeName = null;
if (arguments.length > 1) {
if (arguments[1] instanceof IASTIdExpression) {
IASTIdExpression id = (IASTIdExpression) arguments[1];
IBinding binding = id.getName().resolveBinding();
if (binding instanceof IVariable) {
IType type = ((IVariable) binding).getType();
if (type instanceof ICPPBinding) {
typeName = ASTTypeUtil.getQualifiedName((ICPPBinding) type);
} else {
typeName = type.toString();
}
}
}
}
if (typeName != null) {
ResourceSet rs = component.eResource().getResourceSet();
// assure that some libraries are loaded before checking, ANSI C is already
// loaded by template
PackageUtil.loadPackage(StdUriConstants.UML_PRIM_TYPES_URI, rs);
PackageUtil.loadPackage(URI.createURI("pathmap://ROS2_LIBRARY/ros2Library.uml")/* Helpers.ROS_LIBRARY_URI */, rs);
// can the element be retrieved directly?
NamedElement ne = ElementUtils.getQualifiedElementFromRS(component, typeName);
if (ne == null) {
// check whether in AnsiCLibrary
String qName = "AnsiCLibrary" + NamedElement.SEPARATOR + typeName;
ne = ElementUtils.getQualifiedElementFromRS(component, qName);
}
if (ne == null) {
// try stdlib in ros2 library. Only retrieve stdlib, since ElementUtils do not
// handle separator in type name (as in vector<std::string>)
// (depending on CDT version, __cxx11 namespace is provided)
String shortName = null;
if (typeName.equals("std::__cxx11::string") ||
typeName.equals("std::string")) {
shortName = "string";
} else if (typeName.equals("std::vector<string,allocator<string>>")) {
shortName = "vector<std::string>";
}
if (shortName != null) {
NamedElement stdlib = ElementUtils.getQualifiedElementFromRS(component, "ros2Library::stdlib");
if (stdlib instanceof Package) {
ne = ((Package) stdlib).getMember(shortName);
}
}
}
if (ne instanceof Type) {
ParamInfo paramInfo = getParamInfo(paramName);
paramInfo.name = paramName;
paramInfo.type = (Type) ne;
} else {
Activator.log.debug(String.format("Cannot find type %s", typeName));
}
}
}
public void scanBody(IASTNode node) {
if (node instanceof IASTFunctionCallExpression) {
IASTFunctionCallExpression fCallExpr = (IASTFunctionCallExpression) node;
IASTExpression nameExpr = fCallExpr.getFunctionNameExpression();
if (nameExpr instanceof IASTIdExpression) {
IASTIdExpression nameId = (IASTIdExpression) nameExpr;
IASTName astName = nameId.getName();
String fctName = astName.toString();
EParam param = getProviderFromCall(fctName);
if (param == EParam.ADD_OR_DECLARE) {
obtainDeclOrAddDetails(fCallExpr);
} else if (param == EParam.GET_PARAM) {
obtainGetDetails(fCallExpr);
}
}
}
for (IASTNode child : node.getChildren()) {
// recurse into all children
scanBody(child);
}
}
}