00001
00002
00003
00004
00005
00006
00007
00008
00009 import re
00010 import copy
00011 import rocon_gateway_utils
00012 import rosgraph.impl.graph
00013 import roslib
00014
00015
00016
00017
00018
00019
00020 GATEWAY_GATEWAY_GRAPH = 'gateway_gateway'
00021
00022 GATEWAY_PULLED_GRAPH = 'gateway_pulled'
00023
00024 GATEWAY_FLIPPED_GRAPH = 'gateway_flipped'
00025
00026
00027 def matches_any(name, patternlist):
00028 if patternlist is None or len(patternlist) == 0:
00029 return False
00030 for pattern in patternlist:
00031 if str(name).strip() == pattern:
00032 return True
00033 if re.match("^[a-zA-Z0-9_/]+$", pattern) is None:
00034 if re.match(str(pattern), name.strip()) is not None:
00035 return True
00036 return False
00037
00038
00039 class NodeConnections:
00040 def __init__(self, incoming=None, outgoing=None):
00041 self.incoming = incoming or []
00042 self.outgoing = outgoing or []
00043
00044
00045 class RosGraphDotcodeGenerator:
00046
00047 def __init__(self):
00048 pass
00049
00050 def _add_edge(self, edge, dotcode_factory, dotgraph, is_topic=False):
00051 if is_topic:
00052 dotcode_factory.add_edge_to_graph(dotgraph, edge.start, edge.end, label=edge.label, url='topic:%s' % edge.label)
00053 else:
00054 dotcode_factory.add_edge_to_graph(dotgraph, edge.start, edge.end, label=edge.label)
00055
00056 def _add_node(self, node, rosgraphinst, dotcode_factory, dotgraph):
00057 if node in rosgraphinst.bad_nodes:
00058 bn = rosgraphinst.bad_nodes[node]
00059 if bn.type == rosgraph.impl.graph.BadNode.DEAD:
00060 dotcode_factory.add_node_to_graph(dotgraph,
00061 nodename=node,
00062 shape="doublecircle",
00063 url=node,
00064 color="red")
00065 else:
00066 dotcode_factory.add_node_to_graph(dotgraph,
00067 nodename=node,
00068 shape="doublecircle",
00069 url=node,
00070 color="orange")
00071 else:
00072 dotcode_factory.add_node_to_graph(dotgraph,
00073 nodename=node,
00074
00075
00076 shape='ellipse',
00077 url=rocon_gateway_utils.gateway_basename(node),
00078
00079 )
00080
00081 def _add_topic_node(self, node, dotcode_factory, dotgraph):
00082 label = rosgraph.impl.graph.node_topic(node)
00083 dotcode_factory.add_node_to_graph(dotgraph,
00084 nodename=label,
00085 nodelabel=label,
00086 shape='box',
00087 url="topic:%s" % label)
00088
00089 def generate_namespaces(self, graph, graph_mode):
00090 """
00091 Determine the namespaces of the nodes being displayed
00092 """
00093 namespaces = []
00094 if graph_mode == GATEWAY_GATEWAY_GRAPH:
00095 nodes = graph.gateway_nodes
00096 namespaces = list(set([roslib.names.namespace(n) for n in nodes]))
00097
00098 elif graph_mode == GATEWAY_PULLED_GRAPH or \
00099 graph_mode == GATEWAY_FLIPPED_GRAPH:
00100 gateway_nodes = graph.gateway_nodes
00101 connection_nodes = graph.flipped_nodes
00102 if gateway_nodes or connection_nodes:
00103 namespaces = [roslib.names.namespace(n) for n in gateway_nodes]
00104
00105
00106
00107 namespaces.extend([roslib.names.namespace(n[1:]) for n in connection_nodes])
00108
00109 return list(set(namespaces))
00110
00111 def _filter_orphaned_edges(self, edges, nodes):
00112 nodenames = [str(n).strip() for n in nodes]
00113
00114 return [e for e in edges if e.start.strip() in nodenames and e.end.strip() in nodenames]
00115
00116 def _filter_orphaned_topics(self, connection_nodes, edges):
00117 '''remove topic graphnodes without connected ROS nodes'''
00118 removal_nodes = []
00119 for n in connection_nodes:
00120 keep = False
00121 for e in edges:
00122 if (e.start.strip() == str(n).strip() or e.end.strip() == str(n).strip()):
00123 keep = True
00124 break
00125 if not keep:
00126 removal_nodes.append(n)
00127 for n in removal_nodes:
00128 connection_nodes.remove(n)
00129 return connection_nodes
00130
00131 def _split_filter_string(self, ns_filter):
00132 '''splits a string after each comma, and treats tokens with leading dash as exclusions.
00133 Adds .* as inclusion if no other inclusion option was given'''
00134 includes = []
00135 excludes = []
00136 for name in ns_filter.split(','):
00137 if name.strip().startswith('-'):
00138 excludes.append(name.strip()[1:])
00139 else:
00140 includes.append(name.strip())
00141 if includes == [] or includes == ['/'] or includes == ['']:
00142 includes = ['.*']
00143 return includes, excludes
00144
00145 def _get_node_edge_map(self, edges):
00146 '''returns a dict mapping node name to edge objects partitioned in incoming and outgoing edges'''
00147 node_connections = {}
00148 for edge in edges:
00149 if not edge.start in node_connections:
00150 node_connections[edge.start] = NodeConnections()
00151 if not edge.end in node_connections:
00152 node_connections[edge.end] = NodeConnections()
00153 node_connections[edge.start].outgoing.append(edge)
00154 node_connections[edge.end].incoming.append(edge)
00155 return node_connections
00156
00157 def _filter_leaves(self,
00158 nodes_in,
00159 edges_in,
00160 node_connections,
00161 hide_single_connection_topics,
00162 hide_dead_end_topics):
00163 '''
00164 removes certain ending topic nodes and their edges from list of nodes and edges
00165
00166 @param hide_single_connection_topics: if true removes topics that are only published/subscribed by one node
00167 @param hide_dead_end_topics: if true removes topics having only publishers
00168 '''
00169 if not hide_dead_end_topics and not hide_single_connection_topics:
00170 return nodes_in, edges_in
00171
00172 nodes = copy.copy(nodes_in)
00173 edges = copy.copy(edges_in)
00174 removal_nodes = []
00175 for n in nodes:
00176 if n in node_connections:
00177 node_edges = []
00178 has_out_edges = False
00179 node_edges.extend(node_connections[n].outgoing)
00180 if len(node_connections[n].outgoing) > 0:
00181 has_out_edges = True
00182 node_edges.extend(node_connections[n].incoming)
00183 if ((hide_single_connection_topics and len(node_edges) < 2) or
00184 (hide_dead_end_topics and not has_out_edges)):
00185 removal_nodes.append(n)
00186 for e in node_edges:
00187 if e in edges:
00188 edges.remove(e)
00189 for n in removal_nodes:
00190 nodes.remove(n)
00191 return nodes, edges
00192
00193 def generate_dotgraph(self,
00194 rosgraphinst,
00195 ns_filter,
00196 topic_filter,
00197 graph_mode,
00198 dotcode_factory,
00199 show_all_advertisements=False,
00200 hide_dead_end_topics=False,
00201 cluster_namespaces_level=0,
00202 orientation='LR',
00203 rank='same',
00204 ranksep=0.2,
00205 rankdir='TB',
00206 simplify=True,
00207 ):
00208 """
00209 See generate_dotcode
00210 """
00211 includes, excludes = self._split_filter_string(ns_filter)
00212 connection_includes, connection_excludes = self._split_filter_string(topic_filter)
00213
00214 gateway_nodes = []
00215 connection_nodes = []
00216
00217 if graph_mode == GATEWAY_GATEWAY_GRAPH:
00218 gateway_nodes = rosgraphinst.gateway_nodes
00219 gateway_nodes = [n for n in gateway_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
00220 edges = rosgraphinst.gateway_edges
00221 edges = [e for e in edges if matches_any(e.label, connection_includes) and not matches_any(e.label, connection_excludes)]
00222
00223 elif graph_mode == GATEWAY_PULLED_GRAPH or graph_mode == GATEWAY_FLIPPED_GRAPH:
00224
00225 if graph_mode == GATEWAY_PULLED_GRAPH:
00226 edges = [e for e in rosgraphinst.pulled_edges]
00227 connection_nodes = rosgraphinst.pulled_nodes
00228 else:
00229 edges = [e for e in rosgraphinst.flipped_edges]
00230 connection_nodes = rosgraphinst.flipped_nodes
00231 gateway_nodes = rosgraphinst.gateway_nodes
00232
00233 gateway_nodes = [n for n in gateway_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
00234 connection_nodes = [n for n in connection_nodes if matches_any(n, connection_includes) and not matches_any(n, connection_excludes)]
00235
00236 hide_unused_advertisements = not show_all_advertisements
00237 if graph_mode == GATEWAY_PULLED_GRAPH and hide_unused_advertisements:
00238 node_connections = self._get_node_edge_map(edges)
00239 connection_nodes, edges = self._filter_leaves(connection_nodes,
00240 edges,
00241 node_connections,
00242 hide_unused_advertisements,
00243 hide_dead_end_topics)
00244
00245
00246
00247
00248
00249
00250
00251
00252
00253 edges = self._filter_orphaned_edges(edges, list(gateway_nodes) + list(connection_nodes))
00254 connection_nodes = self._filter_orphaned_topics(connection_nodes, edges)
00255
00256
00257
00258 dotgraph = dotcode_factory.get_graph(rank=rank,
00259 ranksep=ranksep,
00260 simplify=simplify,
00261 rankdir=orientation)
00262
00263 namespace_clusters = {}
00264 for n in (connection_nodes or []):
00265
00266 if (cluster_namespaces_level > 0 and
00267 str(n).count('/') > 1 and
00268 len(str(n).split('/')[1]) > 0):
00269 namespace = str(n).split('/')[1]
00270 if namespace not in namespace_clusters:
00271 namespace_clusters[namespace] = dotcode_factory.add_subgraph_to_graph(dotgraph, namespace, rank=rank, rankdir=orientation, simplify=simplify)
00272 self._add_topic_node(n, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace])
00273 else:
00274 self._add_topic_node(n, dotcode_factory=dotcode_factory, dotgraph=dotgraph)
00275
00276
00277
00278 if gateway_nodes is not None:
00279 for n in gateway_nodes:
00280 if (cluster_namespaces_level > 0 and
00281 str(n).count('/') >= 1 and
00282 len(str(n).split('/')[1]) > 0 and
00283 str(n).split('/')[1] in namespace_clusters):
00284 namespace = str(n).split('/')[1]
00285 self._add_node(n, rosgraphinst=rosgraphinst, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace])
00286 else:
00287 self._add_node(n, rosgraphinst=rosgraphinst, dotcode_factory=dotcode_factory, dotgraph=dotgraph)
00288
00289 for e in edges:
00290 self._add_edge(e, dotcode_factory, dotgraph=dotgraph, is_topic=(graph_mode == GATEWAY_GATEWAY_GRAPH))
00291
00292 return dotgraph
00293
00294 def generate_dotcode(self,
00295 rosgraphinst,
00296 ns_filter,
00297 topic_filter,
00298 graph_mode,
00299 dotcode_factory,
00300 show_all_advertisements=False,
00301 hide_dead_end_topics=False,
00302 cluster_namespaces_level=0,
00303 orientation='LR',
00304 rank='same',
00305 ranksep=0.2,
00306 rankdir='TB',
00307 simplify=True,
00308 ):
00309 """
00310 @param rosgraphinst: RosGraph instance
00311 @param ns_filter: nodename filter
00312 @type ns_filter: string
00313 @param topic_filter: topicname filter
00314 @type ns_filter: string
00315 @param graph_mode str: GATEWAY_GATEWAY_GRAPH | GATEWAY_PULLED_GRAPH | GATEWAY_FLIPPED_GRAPH
00316 @type graph_mode: str
00317 @param orientation: rankdir value (see ORIENTATIONS dict)
00318 @type dotcode_factory: object
00319 @param dotcode_factory: abstract factory manipulating dot language objects
00320 @param hide_single_connection_topics: if true remove topics with just one connection
00321 @param hide_dead_end_topics: if true remove topics with publishers only
00322 @param cluster_namespaces_level: if > 0 places box around members of same namespace (TODO: multiple namespace layers)
00323 @return: dotcode generated from graph singleton
00324 @rtype: str
00325 """
00326 dotgraph = self.generate_dotgraph(rosgraphinst=rosgraphinst,
00327 ns_filter=ns_filter,
00328 topic_filter=topic_filter,
00329 graph_mode=graph_mode,
00330 dotcode_factory=dotcode_factory,
00331 show_all_advertisements=show_all_advertisements,
00332 hide_dead_end_topics=hide_dead_end_topics,
00333 cluster_namespaces_level=cluster_namespaces_level,
00334 orientation=orientation,
00335 rank=rank,
00336 ranksep=ranksep,
00337 rankdir=rankdir,
00338 simplify=simplify,
00339 )
00340 dotcode = dotcode_factory.create_dot(dotgraph)
00341 return dotcode