| /***************************************************************************** |
| * 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.fromsys; |
| |
| import java.io.BufferedReader; |
| import java.io.IOException; |
| import java.io.InputStreamReader; |
| import java.util.ArrayList; |
| import java.util.List; |
| |
| import org.eclipse.core.resources.IFolder; |
| import org.eclipse.core.runtime.IProgressMonitor; |
| import org.eclipse.emf.common.util.URI; |
| import org.eclipse.emf.ecore.resource.Resource; |
| import org.eclipse.emf.ecore.xmi.XMLResource; |
| import org.eclipse.papyrus.designer.languages.common.base.ElementUtils; |
| import org.eclipse.papyrus.designer.languages.common.base.StringConstants; |
| import org.eclipse.papyrus.designer.transformation.base.utils.ModelManagement; |
| import org.eclipse.papyrus.robotics.core.utils.FileExtensions; |
| import org.eclipse.papyrus.robotics.core.utils.ScanUtils; |
| import org.eclipse.papyrus.robotics.library.advice.ActionCommPatternAdvice; |
| import org.eclipse.papyrus.robotics.library.advice.AdviceUtil; |
| import org.eclipse.papyrus.robotics.library.advice.PushCommPatternAdvice; |
| import org.eclipse.papyrus.robotics.library.advice.QueryCommPatternAdvice; |
| import org.eclipse.papyrus.robotics.library.advice.SendCommPatternAdvice; |
| import org.eclipse.papyrus.robotics.profile.robotics.services.ServiceDefinition; |
| import org.eclipse.papyrus.robotics.ros2.reverse.Activator; |
| import org.eclipse.papyrus.robotics.ros2.reverse.Ros2Constants; |
| import org.eclipse.papyrus.robotics.ros2.reverse.fromsys.MessageParser.MessageEntry; |
| import org.eclipse.papyrus.robotics.ros2.reverse.fromsys.MessageParser.NameType; |
| import org.eclipse.papyrus.robotics.ros2.reverse.utils.ReverseUtils; |
| import org.eclipse.papyrus.uml.tools.utils.PackageUtil; |
| import org.eclipse.papyrus.uml.tools.utils.StereotypeUtil; |
| import org.eclipse.uml2.uml.Classifier; |
| import org.eclipse.uml2.uml.DataType; |
| import org.eclipse.uml2.uml.Interface; |
| import org.eclipse.uml2.uml.LiteralInteger; |
| import org.eclipse.uml2.uml.Package; |
| import org.eclipse.uml2.uml.Property; |
| import org.eclipse.uml2.uml.TemplateBinding; |
| import org.eclipse.uml2.uml.TemplateParameter; |
| import org.eclipse.uml2.uml.TemplateParameterSubstitution; |
| import org.eclipse.uml2.uml.TemplateSignature; |
| import org.eclipse.uml2.uml.Type; |
| import org.eclipse.uml2.uml.UMLPackage; |
| |
| public class ReverseMessages { |
| |
| public static final String PATHMAP_ROS2_PRIMITIVE_UML = "pathmap://ROS2_LIBRARY/ros2.primitive.uml"; //$NON-NLS-1$ |
| |
| public enum MessageType { |
| MESSAGE, SERVICE, ACTION, INTERFACES // ALL |
| }; |
| |
| public static void reverseMessages(IFolder folder, IProgressMonitor monitor) { |
| List<MessageEntry> msgList; |
| |
| ProcessBuilder pbIntf = new ProcessBuilder(Ros2Constants.ROS2, Ros2Constants.INTF, Ros2Constants.LIST); |
| monitor.subTask("read interface list"); //$NON-NLS-1$ |
| msgList = readMsgList(folder, monitor, pbIntf); |
| |
| // load primitive types |
| PackageUtil.loadPackage(URI.createURI(PATHMAP_ROS2_PRIMITIVE_UML), ModelManagement.getResourceSet()); |
| monitor.beginTask("reverse ROS messages and services", msgList.size()); //$NON-NLS-1$ |
| |
| for (MessageEntry msg : msgList) { |
| monitor.subTask(msg.name); |
| reverseMsg(msg); |
| |
| if (msg.type.equals(Ros2Constants.MSG)) { |
| // create a service definition for push and send |
| createPushOrSendSvcDefinition(msg, false); |
| createPushOrSendSvcDefinition(msg, true); |
| } else if (msg.type.equals(Ros2Constants.SRV)) { |
| createQuerySvcDefinition(msg); |
| } else if (msg.type.equals(Ros2Constants.ACTION)) { |
| createActionSvcDefinition(msg); |
| } |
| monitor.worked(1); |
| if (monitor.isCanceled()) |
| break; |
| } |
| |
| // save |
| List<Resource> resources = new ArrayList<Resource>(); |
| resources.addAll(ModelManagement.getResourceSet().getResources()); |
| |
| for (Resource r : resources) { |
| try { |
| r.save(null); |
| } catch (IOException e) { |
| Activator.log.error(e); |
| } |
| } |
| } |
| |
| /** |
| * Read the list of messages via the ROS2 command line tool |
| * The associated communication objects are already created (without attributes), in |
| * order to reference these later when assigning attribute types |
| * |
| * @param folder |
| * a folder within a project (into which reversed models will be stored) |
| * @param monitor |
| * a progress monitor |
| * @param pb |
| * a process builder |
| * @return a list of message entries |
| */ |
| public static List<MessageEntry> readMsgList(IFolder folder, IProgressMonitor monitor, ProcessBuilder pb) { |
| List<MessageEntry> msgList = new ArrayList<MessageEntry>(); |
| try { |
| Process p = pb.start(); |
| BufferedReader results = new BufferedReader(new InputStreamReader(p.getInputStream())); |
| StringBuffer errorMsg = new StringBuffer(); |
| boolean error = ReverseUtils.logErrors(p, errorMsg); |
| if (error) |
| return msgList; |
| String line; |
| List<URI> pathMapURIs = ScanUtils.allPathmapModels(FileExtensions.SERVICEDEF_UML); |
| while ((line = results.readLine()) != null) { |
| MessageEntry msg = MessageParser.extractMessageEntry(line); |
| |
| if (msg != null) { |
| Package pkg; |
| if (ReverseUtils.existsAlready(folder, pathMapURIs, msg.pkgName)) { |
| pkg = getBasePkg(msg.pkgName); |
| if (pkg == null) { |
| ReverseUtils.loadMessagePackage(folder, pathMapURIs, msg.pkgName); |
| pkg = getBasePkg(msg.pkgName); |
| } |
| } else { |
| // create ... |
| monitor.subTask("create new model for package " + msg.pkgName); //$NON-NLS-1$ |
| pkg = ReverseUtils.createMsgPackage(folder, msg.pkgName); |
| } |
| if (pkg == null) { |
| Activator.log.debug("a Model for message package %s exists, but does not define the message package"); //$NON-NLS-1$ |
| continue; |
| } |
| boolean added = false; |
| if (msg.type.equals(Ros2Constants.MSG)) { |
| Package msgs = ReverseUtils.getOrCreatePackage(pkg, Ros2Constants.MSG); |
| added = ReverseUtils.getOrCreateCommObject(msgs, msg.commObjects, msg.name); |
| } else if (msg.type.equals(Ros2Constants.SRV)) { |
| Package srvs = ReverseUtils.getOrCreatePackage(pkg, Ros2Constants.SRV); |
| added = ReverseUtils.getOrCreateCommObject(srvs, msg.commObjects, msg.name + Ros2Constants.REQ); |
| added = ReverseUtils.getOrCreateCommObject(srvs, msg.commObjects, msg.name + Ros2Constants.RES) || added; |
| } else if (msg.type.equals(Ros2Constants.ACTION)) { |
| Package actions = ReverseUtils.getOrCreatePackage(pkg, Ros2Constants.ACTION); |
| added = ReverseUtils.getOrCreateCommObject(actions, msg.commObjects, msg.name + Ros2Constants.GOAL); |
| added = ReverseUtils.getOrCreateCommObject(actions, msg.commObjects, msg.name + Ros2Constants.RES) || added; |
| added = ReverseUtils.getOrCreateCommObject(actions, msg.commObjects, msg.name + Ros2Constants.FEEDBACK) || added; |
| } |
| if (added) { |
| msgList.add(msg); |
| } |
| } |
| monitor.worked(1); |
| if (monitor.isCanceled()) |
| break; |
| } |
| results.close(); |
| } catch (IOException exp) { |
| Activator.log.error(exp); |
| } |
| return msgList; |
| } |
| |
| /** |
| * Reverse a single message type, i.e. fill the attributes of allready created communication objects. |
| * |
| * @param msg |
| * a MessageEntry |
| */ |
| public static void reverseMsg(MessageEntry msg) { |
| ProcessBuilder pb; |
| String qMessageName = msg.pkgName + StringConstants.SLASH + msg.type + StringConstants.SLASH + msg.name; |
| pb = new ProcessBuilder(Ros2Constants.ROS2, Ros2Constants.INTF, Ros2Constants.SHOW, qMessageName); |
| List<DataType> commObjects = msg.commObjects; |
| |
| try { |
| Process p = pb.start(); |
| BufferedReader results = new BufferedReader(new InputStreamReader(p.getInputStream())); |
| StringBuffer errorMsg = new StringBuffer(); |
| boolean error = ReverseUtils.logErrors(p, errorMsg); |
| if (error) |
| return; |
| String line; |
| int index = 0; |
| DataType commObject = commObjects.get(index++); |
| while ((line = results.readLine()) != null) { |
| line = MessageParser.filterComment(line); |
| if (line.equals("---")) { //$NON-NLS-1$ |
| // separator request/response => switch to response communication object |
| commObject = commObjects.get(index++); |
| } |
| NameType nt = MessageParser.extractNameType(line); |
| if (nt != null) { |
| String type = nt.typeName; |
| Package pkg; |
| boolean checkPrimitive = false; |
| if (nt.typePkg != null) { |
| pkg = getMessagePkg(nt.typePkg); |
| } else { |
| // no qualification, either in current package or primitive (see below) |
| pkg = getMessagePkg(msg.pkgName); |
| checkPrimitive = true; |
| } |
| Type umlType = pkg != null ? pkg.getOwnedType(type) : null; |
| if (umlType == null && checkPrimitive) { |
| // try in primitive types |
| pkg = (Package) ElementUtils.getQualifiedElementFromRS(commObject, "primitive"); //$NON-NLS-1$ |
| umlType = pkg != null ? pkg.getOwnedType(type) : null; |
| } |
| if (umlType == null) { |
| Activator.log.debug("Cannot find type for " + nt.typeName); //$NON-NLS-1$ |
| } |
| Property attr = commObject.getOwnedAttribute(nt.name, null); |
| if (attr == null) { |
| attr = commObject.createOwnedAttribute(nt.name, null); |
| } |
| attr.setType(umlType); |
| if (nt.upper != null) { |
| attr.setLower(0); |
| attr.setUpper(nt.upper); |
| } |
| if (nt.defaultValue != null) { |
| // value assignment => constant |
| attr.setIsStatic(true); |
| LiteralInteger li = (LiteralInteger) attr.createDefaultValue(null, umlType, |
| UMLPackage.Literals.LITERAL_INTEGER); |
| li.setValue(nt.defaultValue); |
| } |
| } |
| } |
| |
| results.close(); |
| |
| } catch (IOException exp) { |
| Activator.log.error(exp); |
| } |
| } |
| |
| /** |
| * Create a service definition for push or send pattern |
| * |
| * @param msg |
| * a MessageEntry |
| * @param isPush |
| * if true, create Push, else Send |
| */ |
| public static void createPushOrSendSvcDefinition(MessageEntry msg, boolean isPush) { |
| // Service definition |
| DataType commObject = msg.commObjects.get(0); |
| Package pkg = getServiceDefPkg(msg.pkgName); |
| // dummy operation to trigger the loading of the robotics library |
| PackageUtil.getRootPackage(commObject).getMember("robotics"); //$NON-NLS-1$ |
| Classifier commPattern = isPush ? AdviceUtil.getPattern(commObject, PushCommPatternAdvice.PUSH_PATTERN) : AdviceUtil.getPattern(commObject, SendCommPatternAdvice.SEND_PATTERN); |
| if (commPattern != null) { |
| Interface serviceDef = pkg.createOwnedInterface(null); |
| TemplateSignature signature = commPattern.getOwnedTemplateSignature(); |
| TemplateBinding binding = serviceDef.createTemplateBinding(signature); |
| |
| String name = (isPush ? "P_" : "S_") + commObject.getName(); //$NON-NLS-1$ //$NON-NLS-2$ |
| // loop on template parameters; |
| for (TemplateParameter parameter : signature.getOwnedParameters()) { |
| |
| TemplateParameterSubstitution substitution = binding.createParameterSubstitution(); |
| substitution.setFormal(parameter); |
| |
| // now obtain actual from user (code is based on assumption that there is a single message parameter) |
| substitution.setActual(commObject); |
| } |
| serviceDef.setName(name); |
| ((XMLResource) serviceDef.eResource()).setID(serviceDef, pkg.getName() + MessageParser.SLASH + name); |
| StereotypeUtil.apply(serviceDef, ServiceDefinition.class); |
| } |
| } |
| |
| /** |
| * Create a query service definition |
| * |
| * @param msg |
| * a MessageEntry |
| */ |
| public static void createQuerySvcDefinition(MessageEntry msg) { |
| // Service definition |
| DataType commObjectReq = msg.commObjects.get(0); |
| DataType commObjectRes = msg.commObjects.get(1); |
| Package pkg = getServiceDefPkg(msg.pkgName); |
| Classifier queryCommPattern = AdviceUtil.getPattern(commObjectReq, QueryCommPatternAdvice.QUERY_PATTERN); |
| if (queryCommPattern != null) { |
| Interface serviceDef = pkg.createOwnedInterface(null); |
| TemplateSignature signature = queryCommPattern.getOwnedTemplateSignature(); |
| TemplateBinding binding = serviceDef.createTemplateBinding(signature); |
| |
| // typical naming convention |
| String name = "Q_"; //$NON-NLS-1$ |
| String reqName = commObjectReq.getName(); |
| if (reqName.endsWith(Ros2Constants.REQ)) { |
| // append name without Req postfix |
| name += reqName.substring(0, reqName.length() - 3); |
| } else { |
| name += reqName; |
| } |
| // loop on template parameters; |
| boolean first = true; |
| for (TemplateParameter parameter : signature.getOwnedParameters()) { |
| |
| TemplateParameterSubstitution substitution = binding.createParameterSubstitution(); |
| substitution.setFormal(parameter); |
| |
| // now obtain actual from user (code is based on assumption that there is a single message parameter) |
| substitution.setActual(first ? commObjectReq : commObjectRes); |
| first = false; |
| } |
| serviceDef.setName(name); |
| ((XMLResource) serviceDef.eResource()).setID(serviceDef, pkg.getName() + MessageParser.SLASH + name); |
| StereotypeUtil.apply(serviceDef, ServiceDefinition.class); |
| } |
| } |
| |
| /** |
| * Create an action service definition |
| * |
| * @param msg |
| * a MessageEntry |
| */ |
| public static void createActionSvcDefinition(MessageEntry msg) { |
| // Service definition |
| DataType commObjGoal = msg.commObjects.get(0); |
| DataType commObjResult = msg.commObjects.get(1); |
| DataType commObjFeedback = msg.commObjects.get(2); |
| Package pkg = getServiceDefPkg(msg.pkgName); |
| Classifier actionCommPattern = AdviceUtil.getPattern(commObjGoal, ActionCommPatternAdvice.ACTION_PATTERN); |
| // Classifier actionCommPattern = AdviceUtil.getPattern(commObjGoal, ActionCommPatternAdvice.ACTION_PATTERN); |
| if (actionCommPattern != null) { |
| Interface serviceDef = pkg.createOwnedInterface(null); |
| TemplateSignature signature = actionCommPattern.getOwnedTemplateSignature(); |
| TemplateBinding binding = serviceDef.createTemplateBinding(signature); |
| |
| // naming convention |
| String name = "A_"; //$NON-NLS-1$ |
| String reqName = commObjGoal.getName(); |
| if (reqName.endsWith(Ros2Constants.GOAL)) { |
| // append name without Goal postfix |
| name += reqName.substring(0, reqName.length() - 4); |
| } else { |
| name += reqName; |
| } |
| // loop on template parameters; |
| int i = 0; |
| for (TemplateParameter parameter : signature.getOwnedParameters()) { |
| |
| TemplateParameterSubstitution substitution = binding.createParameterSubstitution(); |
| substitution.setFormal(parameter); |
| |
| // now obtain actual from user (code is based on assumption that there is a single message parameter) |
| substitution.setActual(i == 0 ? commObjGoal : i == 1 ? commObjResult : commObjFeedback); |
| i++; |
| } |
| serviceDef.setName(name); |
| ((XMLResource) serviceDef.eResource()).setID(serviceDef, pkg.getName() + MessageParser.SLASH + name); |
| StereotypeUtil.apply(serviceDef, ServiceDefinition.class); |
| } |
| } |
| |
| public static Package getBasePkg(String pkgName) { |
| return (Package) ElementUtils.getQualifiedElementFromRS(ModelManagement.getResourceSet(), pkgName); |
| } |
| |
| public static Package getMessagePkg(String pkgName) { |
| Package pkg = getBasePkg(pkgName); |
| if (pkg != null) { |
| return ReverseUtils.getOrCreatePackage(pkg, Ros2Constants.MSG); |
| } |
| return null; |
| } |
| |
| /** |
| * Obtain a service definition package |
| * |
| * @param pkgName |
| * the name of the sub-package within the service definition package |
| * @return a service definition package |
| */ |
| public static Package getServiceDefPkg(String pkgName) { |
| Package pkg = getBasePkg(pkgName); |
| if (pkg != null) { |
| return ReverseUtils.getOrCreatePackage(pkg, Ros2Constants.SVCDEFS); |
| } |
| return null; |
| } |
| } |