00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import re
00036 import copy
00037
00038 import rosgraph.impl.graph
00039 import roslib
00040 import math
00041
00042 import rospy
00043 import pydot
00044
00045
00046 NODE_NODE_GRAPH = 'node_node'
00047
00048 NODE_TOPIC_GRAPH = 'node_topic'
00049
00050 NODE_TOPIC_ALL_GRAPH = 'node_topic_all'
00051
00052 QUIET_NAMES = ['/diag_agg', '/runtime_logger', '/pr2_dashboard', '/rviz', '/rosout', '/cpu_monitor', '/monitor', '/hd_monitor', '/rxloggerlevel', '/clock', '/rqt', '/statistics']
00053
00054 def _conv(n):
00055 """Convert a node name to a valid dot name, which can't contain the leading space"""
00056 if n.startswith(' '):
00057 return 't_' + n[1:]
00058 else:
00059 return 'n_' + n
00060
00061 def matches_any(name, patternlist):
00062 if patternlist is None or len(patternlist) == 0:
00063 return False
00064 for pattern in patternlist:
00065 if str(name).strip() == pattern:
00066 return True
00067 if re.match("^[a-zA-Z0-9_/]+$", pattern) is None:
00068 if re.match(str(pattern), name.strip()) is not None:
00069 return True
00070 return False
00071
00072
00073 class NodeConnections:
00074 def __init__(self, incoming=None, outgoing=None):
00075 self.incoming = incoming or []
00076 self.outgoing = outgoing or []
00077
00078
00079 class RosGraphDotcodeGenerator:
00080
00081
00082 edges = dict([])
00083
00084
00085 nodes = dict([])
00086
00087 def __init__(self):
00088 try:
00089 from rosgraph_msgs.msg import TopicStatistics
00090 self.stats_sub = rospy.Subscriber('/statistics', TopicStatistics, self.statistics_callback)
00091 except ImportError:
00092
00093 pass
00094
00095 def statistics_callback(self,msg):
00096
00097
00098 if not msg.node_sub in self.edges:
00099 self.edges[msg.node_sub] = dict([])
00100
00101 if not msg.topic in self.edges[msg.node_sub]:
00102 self.edges[msg.node_sub][msg.topic] = dict([])
00103
00104 self.edges[msg.node_sub][msg.topic][msg.node_pub] = msg
00105
00106 def _get_max_traffic(self):
00107 traffic = 10000
00108 for sub in self.edges:
00109 for topic in self.edges[sub]:
00110 for pub in self.edges[sub][topic]:
00111 traffic = max(traffic, self.edges[sub][topic][pub].traffic)
00112 return traffic
00113
00114 def _get_max_age(self):
00115 age = 0.1
00116 for sub in self.edges:
00117 for topic in self.edges[sub]:
00118 for pub in self.edges[sub][topic]:
00119 age = max(age, self.edges[sub][topic][pub].stamp_age_mean.to_sec())
00120 return age
00121
00122 def _get_max_age_on_topic(self, sub, topic):
00123 age = 0.0
00124 for pub in self.edges[sub][topic]:
00125 age = max(age, self.edges[sub][topic][pub].stamp_age_mean.to_sec())
00126 return age
00127
00128 def _calc_edge_color(self, sub, topic, pub=None):
00129
00130 age = 0.0
00131
00132 if pub is None:
00133 age = self._get_max_age_on_topic(sub, topic)
00134 elif sub in self.edges and topic in self.edges[sub] and pub in self.edges[sub][topic]:
00135 age = self.edges[sub][topic][pub].stamp_age_mean.to_sec()
00136
00137 if age == 0.0:
00138 return [0, 0, 0]
00139
00140
00141 heat = max(age, 0) / self._get_max_age()
00142
00143
00144
00145 if heat < 0:
00146 red = 0
00147 green = 0
00148 elif heat <= 0.5:
00149 red = int(heat * 255 * 2)
00150 green = 255
00151 elif heat > 0.5:
00152 red = 255
00153 green = 255 - int((heat - 0.5) * 255 * 2)
00154 else:
00155 red = 0
00156 green = 0
00157 return [red, green, 0]
00158
00159 def _calc_edge_penwidth(self, sub, topic, pub=None):
00160 if pub is None and sub in self.edges and topic in self.edges[sub]:
00161 traffic = 0
00162 for p in self.edges[sub][topic]:
00163 if pub is None or p == pub:
00164 traffic += self.edges[sub][topic][p].traffic
00165
00166
00167 return int(traffic / self._get_max_traffic() * 5)
00168 else:
00169 return 1
00170
00171 def _calc_statistic_info(self, sub, topic, pub=None):
00172 if pub is None and sub in self.edges and topic in self.edges[sub]:
00173 conns = len(self.edges[sub][topic])
00174 if conns == 1:
00175 pub = next(iter(self.edges[sub][topic].keys()))
00176 else:
00177 penwidth = self._calc_edge_penwidth(sub,topic)
00178 color = self._calc_edge_color(sub,topic)
00179 label = "("+str(conns) + " connections)"
00180 return [label, penwidth, color]
00181
00182 if sub in self.edges and topic in self.edges[sub] and pub in self.edges[sub][topic]:
00183 penwidth = self._calc_edge_penwidth(sub,topic,pub)
00184 color = self._calc_edge_color(sub,topic,pub)
00185 period = self.edges[sub][topic][pub].period_mean.to_sec()
00186 if period > 0.0:
00187 freq = str(round(1.0 / period, 1))
00188 else:
00189 freq = "?"
00190 age = self.edges[sub][topic][pub].stamp_age_mean.to_sec()
00191 age_string = ""
00192 if age > 0.0:
00193 age_string = " // " + str(round(age, 2) * 1000) + " ms"
00194 label = freq + " Hz" + age_string
00195 return [label, penwidth, color]
00196 else:
00197 return [None, None, None]
00198
00199 def _add_edge(self, edge, dotcode_factory, dotgraph, is_topic=False):
00200 if is_topic:
00201 sub = edge.end
00202 topic = edge.label
00203 pub = edge.start
00204 [stat_label, penwidth, color] = self._calc_statistic_info(sub, topic, pub)
00205 if stat_label is not None:
00206 temp_label = edge.label + "\\n" + stat_label
00207 dotcode_factory.add_edge_to_graph(dotgraph, _conv(edge.start), _conv(edge.end), label=temp_label, url='topic:%s' % edge.label, penwidth=penwidth, color=color)
00208 else:
00209 dotcode_factory.add_edge_to_graph(dotgraph, _conv(edge.start), _conv(edge.end), label=edge.label, url='topic:%s' % edge.label)
00210 else:
00211 sub = edge.end.strip()
00212 topic = edge.start.strip()
00213 [stat_label, penwidth, color] = self._calc_statistic_info(sub, topic)
00214 if stat_label is not None:
00215 temp_label = edge.label + "\\n" + stat_label
00216 dotcode_factory.add_edge_to_graph(dotgraph, _conv(edge.start), _conv(edge.end), label=temp_label, penwidth=penwidth, color=color)
00217 else:
00218 dotcode_factory.add_edge_to_graph(dotgraph, _conv(edge.start), _conv(edge.end), label=edge.label)
00219
00220
00221 def _add_node(self, node, rosgraphinst, dotcode_factory, dotgraph, unreachable):
00222 if node in rosgraphinst.bad_nodes:
00223 if unreachable:
00224 return ''
00225 bn = rosgraphinst.bad_nodes[node]
00226 if bn.type == rosgraph.impl.graph.BadNode.DEAD:
00227 dotcode_factory.add_node_to_graph(dotgraph,
00228 nodename=_conv(node),
00229 nodelabel=node,
00230 shape="ellipse",
00231 url=node + " (DEAD)",
00232 color="red")
00233 elif bn.type == rosgraph.impl.graph.BadNode.WONKY:
00234 dotcode_factory.add_node_to_graph(dotgraph,
00235 nodename=_conv(node),
00236 nodelabel=node,
00237 shape="ellipse",
00238 url=node + " (WONKY)",
00239 color="orange")
00240 else:
00241 dotcode_factory.add_node_to_graph(dotgraph,
00242 nodename=_conv(node),
00243 nodelabel=node,
00244 shape="ellipse",
00245 url=node + " (UNKNOWN)",
00246 color="red")
00247 else:
00248 dotcode_factory.add_node_to_graph(dotgraph,
00249 nodename=_conv(node),
00250 nodelabel=node,
00251 shape='ellipse',
00252 url=node)
00253
00254 def _add_topic_node(self, node, dotcode_factory, dotgraph, quiet):
00255 label = rosgraph.impl.graph.node_topic(node)
00256 dotcode_factory.add_node_to_graph(dotgraph,
00257 nodename=_conv(node),
00258 nodelabel=label,
00259 shape='box',
00260 url="topic:%s" % label)
00261
00262 def _quiet_filter(self, name):
00263
00264 for n in QUIET_NAMES:
00265 if n in name:
00266 return False
00267 return True
00268
00269 def quiet_filter_topic_edge(self, edge):
00270 for quiet_label in ['/time', '/clock', '/rosout', '/statistics']:
00271 if quiet_label == edge.label:
00272 return False
00273 return self._quiet_filter(edge.start) and self._quiet_filter(edge.end)
00274
00275 def generate_namespaces(self, graph, graph_mode, quiet=False):
00276 """
00277 Determine the namespaces of the nodes being displayed
00278 """
00279 namespaces = []
00280 if graph_mode == NODE_NODE_GRAPH:
00281 nodes = graph.nn_nodes
00282 if quiet:
00283 nodes = [n for n in nodes if not n in QUIET_NAMES]
00284 namespaces = list(set([roslib.names.namespace(n) for n in nodes]))
00285
00286 elif graph_mode == NODE_TOPIC_GRAPH or \
00287 graph_mode == NODE_TOPIC_ALL_GRAPH:
00288 nn_nodes = graph.nn_nodes
00289 nt_nodes = graph.nt_nodes
00290 if quiet:
00291 nn_nodes = [n for n in nn_nodes if not n in QUIET_NAMES]
00292 nt_nodes = [n for n in nt_nodes if not n in QUIET_NAMES]
00293 if nn_nodes or nt_nodes:
00294 namespaces = [roslib.names.namespace(n) for n in nn_nodes]
00295
00296
00297
00298 namespaces.extend([roslib.names.namespace(n[1:]) for n in nt_nodes])
00299
00300 return list(set(namespaces))
00301
00302 def _filter_orphaned_edges(self, edges, nodes):
00303 nodenames = [str(n).strip() for n in nodes]
00304
00305 return [e for e in edges if e.start.strip() in nodenames and e.end.strip() in nodenames]
00306
00307 def _filter_orphaned_topics(self, nt_nodes, edges):
00308 '''remove topic graphnodes without connected ROS nodes'''
00309 removal_nodes = []
00310 for n in nt_nodes:
00311 keep = False
00312 for e in edges:
00313 if (e.start.strip() == str(n).strip() or e.end.strip() == str(n).strip()):
00314 keep = True
00315 break
00316 if not keep:
00317 removal_nodes.append(n)
00318 for n in removal_nodes:
00319 nt_nodes.remove(n)
00320 return nt_nodes
00321
00322 def _split_filter_string(self, ns_filter):
00323 '''splits a string after each comma, and treats tokens with leading dash as exclusions.
00324 Adds .* as inclusion if no other inclusion option was given'''
00325 includes = []
00326 excludes = []
00327 for name in ns_filter.split(','):
00328 if name.strip().startswith('-'):
00329 excludes.append(name.strip()[1:])
00330 else:
00331 includes.append(name.strip())
00332 if includes == [] or includes == ['/'] or includes == ['']:
00333 includes = ['.*']
00334 return includes, excludes
00335
00336 def _get_node_edge_map(self, edges):
00337 '''returns a dict mapping node name to edge objects partitioned in incoming and outgoing edges'''
00338 node_connections = {}
00339 for edge in edges:
00340 if not edge.start in node_connections:
00341 node_connections[edge.start] = NodeConnections()
00342 if not edge.end in node_connections:
00343 node_connections[edge.end] = NodeConnections()
00344 node_connections[edge.start].outgoing.append(edge)
00345 node_connections[edge.end].incoming.append(edge)
00346 return node_connections
00347
00348 def _filter_leaf_topics(self,
00349 nodes_in,
00350 edges_in,
00351 node_connections,
00352 hide_single_connection_topics,
00353 hide_dead_end_topics):
00354 '''
00355 removes certain ending topic nodes and their edges from list of nodes and edges
00356
00357 @param hide_single_connection_topics: if true removes topics that are only published/subscribed by one node
00358 @param hide_dead_end_topics: if true removes topics having only publishers
00359 '''
00360 if not hide_dead_end_topics and not hide_single_connection_topics:
00361 return nodes_in, edges_in
00362
00363 nodes = copy.copy(nodes_in)
00364 edges = copy.copy(edges_in)
00365 removal_nodes = []
00366 for n in nodes:
00367 if n in node_connections:
00368 node_edges = []
00369 has_out_edges = False
00370 node_edges.extend(node_connections[n].outgoing)
00371 if len(node_connections[n].outgoing) > 0:
00372 has_out_edges = True
00373 node_edges.extend(node_connections[n].incoming)
00374 if ((hide_single_connection_topics and len(node_edges) < 2) or
00375 (hide_dead_end_topics and not has_out_edges)):
00376 removal_nodes.append(n)
00377 for e in node_edges:
00378 if e in edges:
00379 edges.remove(e)
00380 for n in removal_nodes:
00381 nodes.remove(n)
00382 return nodes, edges
00383
00384 def _accumulate_action_topics(self, nodes_in, edges_in, node_connections):
00385 '''takes topic nodes, edges and node connections.
00386 Returns topic nodes where action topics have been removed,
00387 edges where the edges to action topics have been removed, and
00388 a map with the connection to each virtual action topic node'''
00389 removal_nodes = []
00390 action_nodes = {}
00391
00392 nodes = copy.copy(nodes_in)
00393 edges = copy.copy(edges_in)
00394 for n in nodes:
00395 if str(n).endswith('/feedback'):
00396 prefix = str(n)[:-len('/feedback')].strip()
00397 action_topic_nodes = []
00398 action_topic_edges_out = set()
00399 action_topic_edges_in = set()
00400 for suffix in ['/status', '/result', '/goal', '/cancel', '/feedback']:
00401 for n2 in nodes:
00402 if str(n2).strip() == prefix + suffix:
00403 action_topic_nodes.append(n2)
00404 if n2 in node_connections:
00405 action_topic_edges_out.update(node_connections[n2].outgoing)
00406 action_topic_edges_in.update(node_connections[n2].incoming)
00407 if len(action_topic_nodes) == 5:
00408
00409 removal_nodes.extend(action_topic_nodes)
00410 for e in action_topic_edges_out:
00411 if e in edges:
00412 edges.remove(e)
00413 for e in action_topic_edges_in:
00414 if e in edges:
00415 edges.remove(e)
00416 action_nodes[prefix] = {'topics': action_topic_nodes,
00417 'outgoing': action_topic_edges_out,
00418 'incoming': action_topic_edges_in}
00419 for n in removal_nodes:
00420 nodes.remove(n)
00421 return nodes, edges, action_nodes
00422
00423 def generate_dotgraph(self,
00424 rosgraphinst,
00425 ns_filter,
00426 topic_filter,
00427 graph_mode,
00428 dotcode_factory,
00429 hide_single_connection_topics=False,
00430 hide_dead_end_topics=False,
00431 cluster_namespaces_level=0,
00432 accumulate_actions=True,
00433 orientation='LR',
00434 rank='same',
00435 ranksep=0.2,
00436 rankdir='TB',
00437 simplify=True,
00438 quiet=False,
00439 unreachable=False):
00440 """
00441 See generate_dotcode
00442 """
00443 includes, excludes = self._split_filter_string(ns_filter)
00444 topic_includes, topic_excludes = self._split_filter_string(topic_filter)
00445
00446 nn_nodes = []
00447 nt_nodes = []
00448
00449 if graph_mode == NODE_NODE_GRAPH:
00450 nn_nodes = rosgraphinst.nn_nodes
00451 nn_nodes = [n for n in nn_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
00452 edges = rosgraphinst.nn_edges
00453 edges = [e for e in edges if matches_any(e.label, topic_includes) and not matches_any(e.label, topic_excludes)]
00454
00455 elif graph_mode == NODE_TOPIC_GRAPH or \
00456 graph_mode == NODE_TOPIC_ALL_GRAPH:
00457 nn_nodes = rosgraphinst.nn_nodes
00458 nt_nodes = rosgraphinst.nt_nodes
00459 nn_nodes = [n for n in nn_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
00460 nt_nodes = [n for n in nt_nodes if matches_any(n, topic_includes) and not matches_any(n, topic_excludes)]
00461
00462
00463 if graph_mode == NODE_TOPIC_GRAPH:
00464 edges = [e for e in rosgraphinst.nt_edges]
00465 else:
00466 edges = [e for e in rosgraphinst.nt_all_edges]
00467
00468 if quiet:
00469 nn_nodes = list(filter(self._quiet_filter, nn_nodes))
00470 nt_nodes = list(filter(self._quiet_filter, nt_nodes))
00471 if graph_mode == NODE_NODE_GRAPH:
00472 edges = list(filter(self.quiet_filter_topic_edge, edges))
00473
00474
00475 action_nodes = {}
00476
00477 if graph_mode != NODE_NODE_GRAPH and (hide_single_connection_topics or hide_dead_end_topics or accumulate_actions):
00478
00479 node_connections = self._get_node_edge_map(edges)
00480
00481 nt_nodes, edges = self._filter_leaf_topics(nt_nodes,
00482 edges,
00483 node_connections,
00484 hide_single_connection_topics,
00485 hide_dead_end_topics)
00486
00487 if accumulate_actions:
00488 nt_nodes, edges, action_nodes = self._accumulate_action_topics(nt_nodes, edges, node_connections)
00489
00490 edges = self._filter_orphaned_edges(edges, nn_nodes + nt_nodes)
00491 nt_nodes = self._filter_orphaned_topics(nt_nodes, edges)
00492
00493
00494
00495 dotgraph = dotcode_factory.get_graph(rank=rank,
00496 ranksep=ranksep,
00497 simplify=simplify,
00498 rankdir=orientation)
00499
00500 ACTION_TOPICS_SUFFIX = '/action_topics'
00501 namespace_clusters = {}
00502 for n in (nt_nodes or []) + [action_prefix + ACTION_TOPICS_SUFFIX for (action_prefix, _) in action_nodes.items()]:
00503
00504 if (cluster_namespaces_level > 0 and
00505 str(n).count('/') > 1 and
00506 len(str(n).split('/')[1]) > 0):
00507 namespace = str(n).split('/')[1]
00508 if namespace not in namespace_clusters:
00509 namespace_clusters[namespace] = dotcode_factory.add_subgraph_to_graph(dotgraph, namespace, rank=rank, rankdir=orientation, simplify=simplify)
00510 self._add_topic_node(n, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace], quiet=quiet)
00511 else:
00512 self._add_topic_node(n, dotcode_factory=dotcode_factory, dotgraph=dotgraph, quiet=quiet)
00513
00514
00515
00516 if nn_nodes is not None:
00517 for n in nn_nodes:
00518 if (cluster_namespaces_level > 0 and
00519 str(n).count('/') > 1 and
00520 len(str(n).split('/')[1]) > 0):
00521 namespace = str(n).split('/')[1]
00522 if namespace not in namespace_clusters:
00523 namespace_clusters[namespace] = dotcode_factory.add_subgraph_to_graph(dotgraph, namespace, rank=rank, rankdir=orientation, simplify=simplify)
00524 self._add_node(n, rosgraphinst=rosgraphinst, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace], unreachable=unreachable)
00525 else:
00526 self._add_node(n, rosgraphinst=rosgraphinst, dotcode_factory=dotcode_factory, dotgraph=dotgraph, unreachable=unreachable)
00527
00528 for e in edges:
00529 self._add_edge(e, dotcode_factory, dotgraph=dotgraph, is_topic=(graph_mode == NODE_NODE_GRAPH))
00530
00531 for (action_prefix, node_connections) in action_nodes.items():
00532 for out_edge in node_connections.get('outgoing', []):
00533 dotcode_factory.add_edge_to_graph(dotgraph, _conv(action_prefix + ACTION_TOPICS_SUFFIX), _conv(out_edge.end))
00534 for in_edge in node_connections.get('incoming', []):
00535 dotcode_factory.add_edge_to_graph(dotgraph, _conv(in_edge.start), _conv(action_prefix + ACTION_TOPICS_SUFFIX))
00536 return dotgraph
00537
00538 def generate_dotcode(self,
00539 rosgraphinst,
00540 ns_filter,
00541 topic_filter,
00542 graph_mode,
00543 dotcode_factory,
00544 hide_single_connection_topics=False,
00545 hide_dead_end_topics=False,
00546 cluster_namespaces_level=0,
00547 accumulate_actions=True,
00548 orientation='LR',
00549 rank='same',
00550 ranksep=0.2,
00551 rankdir='TB',
00552 simplify=True,
00553 quiet=False,
00554 unreachable=False):
00555 """
00556 @param rosgraphinst: RosGraph instance
00557 @param ns_filter: nodename filter
00558 @type ns_filter: string
00559 @param topic_filter: topicname filter
00560 @type ns_filter: string
00561 @param graph_mode str: NODE_NODE_GRAPH | NODE_TOPIC_GRAPH | NODE_TOPIC_ALL_GRAPH
00562 @type graph_mode: str
00563 @param orientation: rankdir value (see ORIENTATIONS dict)
00564 @type dotcode_factory: object
00565 @param dotcode_factory: abstract factory manipulating dot language objects
00566 @param hide_single_connection_topics: if true remove topics with just one connection
00567 @param hide_dead_end_topics: if true remove topics with publishers only
00568 @param cluster_namespaces_level: if > 0 places box around members of same namespace (TODO: multiple namespace layers)
00569 @param accumulate_actions: if true each 5 action topic graph nodes are shown as single graph node
00570 @return: dotcode generated from graph singleton
00571 @rtype: str
00572 """
00573 dotgraph = self.generate_dotgraph(rosgraphinst=rosgraphinst,
00574 ns_filter=ns_filter,
00575 topic_filter=topic_filter,
00576 graph_mode=graph_mode,
00577 dotcode_factory=dotcode_factory,
00578 hide_single_connection_topics=hide_single_connection_topics,
00579 hide_dead_end_topics=hide_dead_end_topics,
00580 cluster_namespaces_level=cluster_namespaces_level,
00581 accumulate_actions=accumulate_actions,
00582 orientation=orientation,
00583 rank=rank,
00584 ranksep=ranksep,
00585 rankdir=rankdir,
00586 simplify=simplify,
00587 quiet=quiet,
00588 unreachable=unreachable)
00589 dotcode = dotcode_factory.create_dot(dotgraph)
00590 return dotcode