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