blob: 0419e5c822f4b3c926b954a6d0ca4c0dbe6fb076 [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.fromsys;
import java.io.BufferedReader;
import java.io.IOException;
import java.io.InputStreamReader;
import java.util.ArrayList;
import java.util.HashMap;
import java.util.List;
import java.util.Map;
import org.eclipse.core.resources.IFile;
import org.eclipse.core.resources.IFolder;
import org.eclipse.core.resources.IProject;
import org.eclipse.core.resources.IWorkspaceRoot;
import org.eclipse.core.resources.ResourcesPlugin;
import org.eclipse.core.runtime.CoreException;
import org.eclipse.core.runtime.IProgressMonitor;
import org.eclipse.core.runtime.NullProgressMonitor;
import org.eclipse.core.runtime.Path;
import org.eclipse.emf.common.util.URI;
import org.eclipse.emf.ecore.resource.Resource;
import org.eclipse.emf.transaction.RecordingCommand;
import org.eclipse.gmf.runtime.notation.Diagram;
import org.eclipse.jface.dialogs.MessageDialog;
import org.eclipse.papyrus.designer.infra.base.StringUtils;
import org.eclipse.papyrus.designer.languages.cpp.library.CppUriConstants;
import org.eclipse.papyrus.designer.transformation.base.utils.ModelManagement;
import org.eclipse.papyrus.designer.uml.tools.utils.ElementUtils;
import org.eclipse.papyrus.infra.core.resource.BadArgumentExcetion;
import org.eclipse.papyrus.infra.core.resource.NotFoundException;
import org.eclipse.papyrus.infra.core.services.ServiceException;
import org.eclipse.papyrus.infra.gmfdiag.common.model.NotationModel;
import org.eclipse.papyrus.robotics.core.utils.FileExtensions;
import org.eclipse.papyrus.robotics.core.utils.ParameterUtils;
import org.eclipse.papyrus.robotics.core.utils.ScanUtils;
import org.eclipse.papyrus.robotics.profile.robotics.components.ComponentDefinitionModel;
import org.eclipse.papyrus.robotics.profile.robotics.components.ComponentInstance;
import org.eclipse.papyrus.robotics.profile.robotics.generics.Connects;
import org.eclipse.papyrus.robotics.profile.robotics.parameters.ParameterEntry;
import org.eclipse.papyrus.robotics.ros2.base.ProcessUtils;
import org.eclipse.papyrus.robotics.ros2.base.Ros2Constants;
import org.eclipse.papyrus.robotics.ros2.base.Ros2ProcessBuilder;
import org.eclipse.papyrus.robotics.ros2.reverse.PortInfo;
import org.eclipse.papyrus.robotics.ros2.reverse.PortInfo.PortKind;
import org.eclipse.papyrus.robotics.ros2.reverse.ReverseConstants;
import org.eclipse.papyrus.robotics.ros2.reverse.fromsys.MessageParser.MessageEntry;
import org.eclipse.papyrus.robotics.ros2.reverse.utils.CreatePortUtils;
import org.eclipse.papyrus.robotics.ros2.reverse.utils.FolderUtils;
import org.eclipse.papyrus.robotics.ros2.reverse.utils.ModelTemplate;
import org.eclipse.papyrus.robotics.ros2.reverse.utils.ReverseUtils;
import org.eclipse.papyrus.robotics.ros2.reverse.utils.ServiceDefUtils;
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.swt.widgets.Display;
import org.eclipse.uml2.uml.Class;
import org.eclipse.uml2.uml.Connector;
import org.eclipse.uml2.uml.ConnectorEnd;
import org.eclipse.uml2.uml.Interface;
import org.eclipse.uml2.uml.NamedElement;
import org.eclipse.uml2.uml.Package;
import org.eclipse.uml2.uml.Property;
import org.eclipse.uml2.uml.Type;
import org.eclipse.uml2.uml.UMLPackage;
/**
* Reverse existing ROS2 nodes. The reversal is based on the ROS2 command line tool:
* 1. The set of nodes is obtained using "ros2 node list"
* 2. The information about the ports of each node is obtained using "ros2 node info <nodename>""
*/
@SuppressWarnings("nls")
public class ReverseNodes {
protected IProgressMonitor monitor;
protected List<URI> pathMapURIs;
protected List<NodeInfo> niList;
protected Map<String, List<NodeInfo>> portHash;
protected int response;
protected static int DIALOG_NO = 0;
protected static int DIALOG_YES = 1;
protected static int DIALOG_NO_ALL = 2;
protected static int DIALOG_YES_ALL = 3;
protected class UIQuestion implements Runnable {
UIQuestion(String fileName) {
this.fileName = fileName;
}
protected String fileName;
@Override
public void run() {
response = MessageDialog.open(MessageDialog.QUESTION, Display.getDefault().getActiveShell(),
"Overwrite model?",
String.format(
"A model for the node exists already (at the default location \"%s\"). Should it (and eventually subsequent existing ones) be overwritten?", fileName),
MessageDialog.DIALOG_DEFAULT_BOUNDS, "no", "yes", "no to all", "yes to all");
}
};
public ReverseNodes(IProgressMonitor monitor) {
this.monitor = monitor;
for (Resource resource : ModelManagement.getResourceSet().getResources()) {
resource.unload();
}
ModelManagement.getResourceSet().getResources().clear();
pathMapURIs = ScanUtils.allPathmapModels(FileExtensions.SERVICEDEF_UML);
niList = new ArrayList<NodeInfo>();
portHash = new HashMap<String, List<NodeInfo>>();
response = DIALOG_YES;
}
/**
* read the list of nodes and create models.
*/
public void readNodeList() {
Ros2ProcessBuilder pb = new Ros2ProcessBuilder(Ros2Constants.NODE, Ros2Constants.LIST);
try {
Process p = pb.start();
BufferedReader results = new BufferedReader(new InputStreamReader(p.getInputStream()));
boolean error = ProcessUtils.logErrors(p);
if (error) {
return;
}
// first, read all lines into an array in order to calculate
// the number of nodes
String line1;
List<String> lines = new ArrayList<String>();
while ((line1 = results.readLine()) != null) {
String frags[] = line1.split(MessageParser.SLASH);
if (frags.length >= 2) {
String name = frags[1].trim();
if (name.endsWith("_rclcpp_node") || name.endsWith("_client_node") ||
name.startsWith("transform_listener_") || name.startsWith("launch_ros_")) {
// skip
} else {
lines.add(line1);
}
}
}
results.close();
monitor.beginTask("reverse nodes", lines.size() + 1);
for (String line : lines) {
reverseNode(line);
monitor.worked(1);
if (monitor.isCanceled())
break;
}
createSystem();
} catch (IOException | CoreException exp) {
Activator.log.error(exp);
}
}
public void reverseNode(String line) {
String frags[] = line.split(MessageParser.SLASH);
try {
// TODO: always right? (possible that size > 3?)
int top = (frags.length == 3) ? 1 : 0;
String pkgName = frags[top].trim();
final String name = frags[top+1].trim();
monitor.subTask("reverse component " + name);
String fileName = name + FileExtensions.COMPDEF_UML;
// pass complete filename (a bit abusing the extension attribute)
IWorkspaceRoot root = ResourcesPlugin.getWorkspace().getRoot();
if (pkgName.length() == 0) {
IProject project = FolderUtils.obtainProject(fileName);
if (project != null) {
pkgName = project.getName();
} else {
// could not determine
pkgName = name;
}
}
IProject project = root.getProject(pkgName);
IProgressMonitor progressMonitor = new NullProgressMonitor();
if (!project.exists()) {
project.create(progressMonitor);
}
if (!project.isOpen()) {
project.open(progressMonitor);
}
NodeInfo ni = new NodeInfo();
ni.name = name;
IFolder fModels = FolderUtils.createFolderStructure(project);
IFolder fComponents = FolderUtils.getComponentFolder(fModels);
IFile fCompModel = fComponents.getFile(fileName);
URI newURI = URI.createURI("platform:/resource/" + pkgName + "/models/components/" + fileName);
// Does the model already exist? Only ask again, if user responded with YES or NO before
// (not one of the "all options")
if (fCompModel.exists() && (response == DIALOG_NO || response == DIALOG_YES)) {
Display.getDefault().syncExec(new UIQuestion(fCompModel.toString()));
}
if (!fCompModel.exists() || response == DIALOG_YES || response == DIALOG_YES_ALL) {
ModelTemplate mt = new ModelTemplate(newURI, "compdef");
final NotationModel notation = mt.getNotationModel();
final Package pkg = mt.getUMLModel();
// load primitive types
PackageUtil.loadPackage(URI.createURI(ReverseMessages.PATHMAP_ROS2_PRIMITIVE_UML), pkg.eResource().getResourceSet());
PackageUtil.loadPackage(CppUriConstants.ANSIC_LIB_URI, pkg.eResource().getResourceSet());
final String lineFinal = line;
RecordingCommand reverseComponent = new RecordingCommand(mt.getDomain()) {
@Override
protected void doExecute() {
// mark component as external (=> no code generation)
ComponentDefinitionModel cd = StereotypeUtil.applyApp(pkg, ComponentDefinitionModel.class);
cd.setExternal(true);
pkg.setName(name);
ReverseUtils.setXmlID(pkg);
Class clazz = (Class) pkg.getOwnedType(ReverseConstants.MODEL_NAME_UC);
ni.type = clazz;
clazz.setName(name);
ReverseUtils.setXmlID(clazz);
reversePorts(clazz, ni, lineFinal, false);
reverseParams(clazz, lineFinal);
Diagram diagram;
try {
diagram = notation.getDiagram(ReverseConstants.MODEL_NAME_UC);
final String newName = StringUtils.upperCaseFirst(name) + " diagram";
diagram.setName(newName);
} catch (NotFoundException | BadArgumentExcetion e) {
e.printStackTrace();
}
}
};
mt.executeCmd(reverseComponent);
mt.save(progressMonitor);
mt.dispose();
} else {
// obtain clazz
Resource r = ModelManagement.getResourceSet().getResource(newURI, true);
Package rootPkg = (Package) r.getContents().get(0);
// retrieve first class in Model
NamedElement ne = rootPkg.getOwnedMember(null, false, UMLPackage.eINSTANCE.getClass_());
if (ne instanceof Class) {
ni.type = (Class) ne;
} else {
Activator.log.debug("not found");
}
// reverse ports without updating the component (in order to fill port hashMap)
reversePorts(ni.type, ni, line, true);
}
niList.add(ni);
} catch (CoreException | ServiceException e) {
e.printStackTrace();
}
}
public void createSystem() throws CoreException {
String fileName = "fromRos.uml";
IWorkspaceRoot root = ResourcesPlugin.getWorkspace().getRoot();
IFile systemModel = root.getFile(new Path("/reverse/models/system/" + fileName));
if (systemModel.exists()) {
// ask again, unless previous response was not one of the "all" options
if (response == DIALOG_NO || response == DIALOG_YES) {
Display.getDefault().syncExec(new UIQuestion(systemModel.toString()));
}
if (!(response == DIALOG_YES || response == DIALOG_YES_ALL)) {
return;
}
}
String pkgName = "reverse";
IProject project = root.getProject(pkgName);
IProgressMonitor progressMonitor = new NullProgressMonitor();
if (!project.exists()) {
project.create(progressMonitor);
}
if (!project.isOpen()) {
project.open(progressMonitor);
}
FolderUtils.createFolderStructure(project);
URI newURI = URI.createURI("platform:/resource/reverse/models/system/" + fileName);
try {
ModelTemplate mt = new ModelTemplate(newURI, "system");
RecordingCommand rc = new RecordingCommand(mt.getDomain()) {
@Override
protected void doExecute() {
Package root = mt.getUMLModel();
Diagram diagram;
try {
diagram = mt.getNotationModel().getDiagram(ReverseConstants.MODEL_NAME_UC);
diagram.setName("System diagram");
} catch (NotFoundException | BadArgumentExcetion e) {
Activator.log.error(e);
;
}
Class system = (Class) root.getOwnedMember("System");
ReverseUtils.setXmlID(system);
// create instances
for (NodeInfo ni : niList) {
if (system.getMember(ni.name) == null) {
Property instance = system.createOwnedAttribute(ni.name, ni.type);
ReverseUtils.setXmlID(instance);
ComponentInstance ci = StereotypeUtil.applyApp(instance, ComponentInstance.class);
ReverseUtils.setXmlID(ci, "ID_ST_" + ni.name);
}
}
for (String portName : portHash.keySet()) {
Connector c = system.createOwnedConnector(null);
StereotypeUtil.applyApp(c, Connects.class);
String cname = "";
for (NodeInfo ni : portHash.get(portName)) {
// ignore connections to visualization/simulation nodes
if (!ni.name.equals("rviz") && !ni.name.equals("gazebo")) {
ConnectorEnd end = c.createEnd();
end.setPartWithPort(system.getAttribute(ni.name, null));
if (ni.type != null) {
end.setRole(ni.type.getOwnedPort(portName, null));
}
cname += "_" + ni.name;
}
}
ReverseUtils.setXmlID(c, "ID_C" + cname);
if (c.getEnds().size() < 2) {
c.destroy();
}
}
}
};
mt.executeCmd(rc);
mt.save(monitor);
} catch (ServiceException e) {
Activator.log.error(e);
;
}
}
/**
* Reverse ports and add them to the passed component
*
* @param component
* the component
* @param ni
* the node info
* @param qName
* the qualified name of the component (passed to ros2 command line tool)
* @param readOnly
* if true, only fill fill passed node info, don't update component
*/
public void reversePorts(Class component, NodeInfo ni, String qName, boolean readOnly) {
Ros2ProcessBuilder pb = new Ros2ProcessBuilder(Ros2Constants.NODE, Ros2Constants.INFO, qName);
try {
Process p = pb.start();
BufferedReader results = new BufferedReader(new InputStreamReader(p.getInputStream()));
boolean error = ProcessUtils.logErrors(p);
if (error) {
return;
}
String line;
PortKind currentPK = PortKind.PUBLISHER;
while ((line = results.readLine()) != null) {
line = MessageParser.filterComment(line);
if (line.contains("Publishers:")) {
currentPK = PortKind.PUBLISHER;
} else if (line.contains("Subscribers:")) {
currentPK = PortKind.SUBSCRIBER;
} else if (line.contains("Service Servers:")) {
currentPK = PortKind.SERVER;
} else if (line.contains("Service Clients:")) {
currentPK = PortKind.CLIENT;
} else if (line.contains("Action Servers:")) {
currentPK = PortKind.ACTION_SRV;
} else if (line.contains("Action Clients:")) {
currentPK = PortKind.ACTION_CLI;
} else {
String frags[] = line.split(MessageParser.COLON);
if (frags.length == 2) {
String qPortName = frags[0].trim();
String qMessageName = frags[1].trim();
MessageEntry entry = MessageParser.extractMessageEntry(qMessageName);
if (entry.pkgName.equals("rcl_interfaces")
|| entry.pkgName.equals("lifecycle_msgs")
|| entry.pkgName.equals("rosgraph_msgs")) {
// length 3, e.g. "/ROSadder/change_state: lifecycle_msgs/srv/ChangeState" indicate automatically
// standard interfaces
// TODO - might need info whether a lifecycle node.
continue;
}
String portName = qPortName.trim().substring(1);
List<NodeInfo> niWithName = portHash.get(portName);
if (niWithName == null) {
niWithName = new ArrayList<NodeInfo>();
}
niWithName.add(ni);
portHash.put(portName, niWithName);
Interface sd = ServiceDefUtils.getServiceDef(component, pathMapURIs, currentPK, entry);
if (sd == null) {
break;
}
PortInfo pi = new PortInfo();
ni.ports.add(pi);
pi.dtQName = portName;
pi.pk = currentPK;
pi.topic = portName;
if (!readOnly) {
CreatePortUtils.createPort(component, pi, sd);
}
}
}
}
results.close();
} catch (IOException exp) {
Activator.log.error(exp);
}
}
public void reverseParams(Class component, String qName) {
Ros2ProcessBuilder pb = new Ros2ProcessBuilder(Ros2Constants.PARAM, Ros2Constants.LIST, qName);
try {
Process p = pb.start();
BufferedReader results = new BufferedReader(new InputStreamReader(p.getInputStream()));
boolean error = ProcessUtils.logErrors(p);
if (error) {
return;
}
String line;
// read list of ROS parameters and add these to the list of parameters of the
// describe command
Ros2ProcessBuilder pbDesc = new Ros2ProcessBuilder(Ros2Constants.PARAM, Ros2Constants.DESCRIBE, qName);
while (results.ready() && (line = results.readLine()) != null) {
String param = line.trim();
pbDesc.command().add(param);
}
results.close();
String paramName = "";
Class paramSet = ParameterUtils.getParameterClass(component);
// now obtain type
Process pDesc = pbDesc.start();
results = new BufferedReader(new InputStreamReader(pDesc.getInputStream()));
error = ProcessUtils.logErrors(pDesc);
while (results.ready() && (line = results.readLine()) != null) {
String desc = line.trim();
if (desc.startsWith("Parameter name:")) {
paramName = desc.substring("Parameter name:".length()).trim();
}
if (desc.startsWith("Type:")) {
String type = desc.substring(5).trim();
int upper = 1;
if (type.equals("string array")) { // TODO - right mapping?
type = "string";
upper = -1;
}
String name = "primitive" + NamedElement.SEPARATOR + type;
NamedElement ne = ElementUtils.getQualifiedElementFromRS(component, name);
if (ne == null) {
if (type.equals("boolean")) {
type = "bool";
}
if (type.equals("integer")) {
type = "int";
}
name = "AnsiCLibrary" + NamedElement.SEPARATOR + type;
ne = ElementUtils.getQualifiedElementFromRS(component, name);
}
Property paramUML = paramSet.createOwnedAttribute(paramName, (Type) ne);
StereotypeUtil.apply(paramUML, ParameterEntry.class);
if (upper != 1) {
paramUML.setUpper(upper);
}
if (ne == null) {
Activator.log.debug(String.format("Cannot find type %s", type));
}
}
}
results.close();
} catch (IOException exp) {
Activator.log.error(exp);
}
}
}