dotcode.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2008, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 
00033 # this is a modified version of rx/rxgraph/src/rxgraph/dotcode.py
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 try:
00046     unicode
00047     # we're on python2, or the "unicode" function has already been defined elsewhere
00048 except NameError:
00049     unicode = str
00050     # we're on python3
00051 
00052 # node/node connectivity
00053 NODE_NODE_GRAPH = 'node_node'
00054 # node/topic connections where an actual network connection exists
00055 NODE_TOPIC_GRAPH = 'node_topic'
00056 # all node/topic connections, even if no actual network connection
00057 NODE_TOPIC_ALL_GRAPH = 'node_topic_all'
00058 
00059 QUIET_NAMES = ['/diag_agg', '/runtime_logger', '/pr2_dashboard', '/rviz',
00060                '/rosout', '/cpu_monitor', '/monitor', '/hd_monitor',
00061                '/rxloggerlevel', '/clock', '/rqt', '/statistics']
00062 
00063 
00064 def _conv(n):
00065     """Convert a node name to a valid dot name, which can't contain the leading space"""
00066     if n.startswith(' '):
00067         return 't_' + n[1:]
00068     else:
00069         return 'n_' + n
00070 
00071 
00072 def matches_any(name, patternlist):
00073     if patternlist is None or len(patternlist) == 0:
00074         return False
00075     for pattern in patternlist:
00076         if unicode(name).strip() == pattern:
00077             return True
00078         if re.match("^[a-zA-Z0-9_/]+$", pattern) is None:
00079             if re.match(unicode(pattern), name.strip()) is not None:
00080                 return True
00081     return False
00082 
00083 
00084 class NodeConnections:
00085 
00086     def __init__(self, incoming=None, outgoing=None):
00087         self.incoming = incoming or []
00088         self.outgoing = outgoing or []
00089 
00090 
00091 class RosGraphDotcodeGenerator:
00092 
00093     # topic/topic -> graph.edge object
00094     edges = dict([])
00095 
00096     # ROS node name -> graph.node object
00097     nodes = dict([])
00098 
00099     def __init__(self):
00100         try:
00101             from rosgraph_msgs.msg import TopicStatistics
00102             self.stats_sub = rospy.Subscriber(
00103                 '/statistics', TopicStatistics, self.statistics_callback)
00104         except ImportError:
00105             # not supported before Indigo
00106             pass
00107 
00108     def statistics_callback(self, msg):
00109 
00110         # add connections (if new)
00111         if msg.node_sub not in self.edges:
00112             self.edges[msg.node_sub] = dict([])
00113 
00114         if msg.topic not in self.edges[msg.node_sub]:
00115             self.edges[msg.node_sub][msg.topic] = dict([])
00116 
00117         self.edges[msg.node_sub][msg.topic][msg.node_pub] = msg
00118 
00119     def _get_max_traffic(self):
00120         traffic = 10000  # start at 10kb
00121         for sub in self.edges:
00122             for topic in self.edges[sub]:
00123                 for pub in self.edges[sub][topic]:
00124                     traffic = max(traffic, self.edges[sub][topic][pub].traffic)
00125         return traffic
00126 
00127     def _get_max_age(self):
00128         age = 0.1  # start at 100ms
00129         for sub in self.edges:
00130             for topic in self.edges[sub]:
00131                 for pub in self.edges[sub][topic]:
00132                     age = max(age, self.edges[sub][topic][pub].stamp_age_mean.to_sec())
00133         return age
00134 
00135     def _get_max_age_on_topic(self, sub, topic):
00136         age = 0.0
00137         for pub in self.edges[sub][topic]:
00138             age = max(age, self.edges[sub][topic][pub].stamp_age_mean.to_sec())
00139         return age
00140 
00141     def _calc_edge_color(self, sub, topic, pub=None):
00142 
00143         age = 0.0
00144 
00145         if pub is None:
00146             age = self._get_max_age_on_topic(sub, topic)
00147         elif sub in self.edges and topic in self.edges[sub] and pub in self.edges[sub][topic]:
00148             age = self.edges[sub][topic][pub].stamp_age_mean.to_sec()
00149 
00150         if age == 0.0:
00151             return [0, 0, 0]
00152 
00153         # calc coloring using the age
00154         heat = max(age, 0) / self._get_max_age()
00155 
00156         # we assume that heat is normalized between 0.0 (green) and 1.0 (red)
00157         # 0.0->green(0,255,0) to 0.5->yellow (255,255,0) to red 1.0(255,0,0)
00158         if heat < 0:
00159             red = 0
00160             green = 0
00161         elif heat <= 0.5:
00162             red = int(heat * 255 * 2)
00163             green = 255
00164         elif heat > 0.5:
00165             red = 255
00166             green = 255 - int((heat - 0.5) * 255 * 2)
00167         else:
00168             red = 0
00169             green = 0
00170         return [red, green, 0]
00171 
00172     def _calc_edge_penwidth(self, sub, topic, pub=None):
00173         if pub is None and sub in self.edges and topic in self.edges[sub]:
00174             traffic = 0
00175             for p in self.edges[sub][topic]:
00176                 if pub is None or p == pub:
00177                     traffic += self.edges[sub][topic][p].traffic
00178 
00179             # calc penwidth using the traffic in kb/s
00180             return int(traffic / self._get_max_traffic() * 5)
00181         else:
00182             return 1
00183 
00184     def _calc_statistic_info(self, sub, topic, pub=None):
00185         if pub is None and sub in self.edges and topic in self.edges[sub]:
00186             conns = len(self.edges[sub][topic])
00187             if conns == 1:
00188                 pub = next(iter(self.edges[sub][topic].keys()))
00189             else:
00190                 penwidth = self._calc_edge_penwidth(sub, topic)
00191                 color = self._calc_edge_color(sub, topic)
00192                 label = "(" + unicode(conns) + " connections)"
00193                 return [label, penwidth, color]
00194 
00195         if sub in self.edges and topic in self.edges[sub] and pub in self.edges[sub][topic]:
00196             penwidth = self._calc_edge_penwidth(sub, topic, pub)
00197             color = self._calc_edge_color(sub, topic, pub)
00198             period = self.edges[sub][topic][pub].period_mean.to_sec()
00199             if period > 0.0:
00200                 freq = unicode(round(1.0 / period, 1))
00201             else:
00202                 freq = "?"
00203             age = self.edges[sub][topic][pub].stamp_age_mean.to_sec()
00204             age_string = ""
00205             if age > 0.0:
00206                 age_string = " // " + unicode(round(age, 2) * 1000) + " ms"
00207             label = freq + " Hz" + age_string
00208             return [label, penwidth, color]
00209         else:
00210             return [None, None, None]
00211 
00212     def _add_edge(self, edge, dotcode_factory, dotgraph, is_topic=False):
00213         if is_topic:
00214             sub = edge.end
00215             topic = edge.label
00216             pub = edge.start
00217             [stat_label, penwidth, color] = self._calc_statistic_info(sub, topic, pub)
00218             if stat_label is not None:
00219                 temp_label = edge.label + "\\n" + stat_label
00220                 dotcode_factory.add_edge_to_graph(
00221                     dotgraph,
00222                     _conv(edge.start),
00223                     _conv(edge.end),
00224                     label=temp_label,
00225                     url='topic:%s' % edge.label,
00226                     penwidth=penwidth,
00227                     color=color)
00228             else:
00229                 dotcode_factory.add_edge_to_graph(
00230                     dotgraph,
00231                     _conv(edge.start),
00232                     _conv(edge.end),
00233                     label=edge.label,
00234                     url='topic:%s' % edge.label)
00235         else:
00236             sub = edge.end.strip()
00237             topic = edge.start.strip()
00238             [stat_label, penwidth, color] = self._calc_statistic_info(sub, topic)
00239             if stat_label is not None:
00240                 temp_label = edge.label + "\\n" + stat_label
00241                 dotcode_factory.add_edge_to_graph(
00242                     dotgraph,
00243                     _conv(edge.start),
00244                     _conv(edge.end),
00245                     label=temp_label,
00246                     penwidth=penwidth,
00247                     color=color)
00248             else:
00249                 dotcode_factory.add_edge_to_graph(
00250                     dotgraph, _conv(edge.start), _conv(edge.end), label=edge.label)
00251 
00252     def _add_node(self, node, rosgraphinst, dotcode_factory, dotgraph, unreachable):
00253         if node in rosgraphinst.bad_nodes:
00254             if unreachable:
00255                 return ''
00256             bn = rosgraphinst.bad_nodes[node]
00257             if bn.type == rosgraph.impl.graph.BadNode.DEAD:
00258                 dotcode_factory.add_node_to_graph(
00259                     dotgraph,
00260                     nodename=_conv(node),
00261                     nodelabel=node,
00262                     shape="ellipse",
00263                     url=node + " (DEAD)",
00264                     color="red")
00265             elif bn.type == rosgraph.impl.graph.BadNode.WONKY:
00266                 dotcode_factory.add_node_to_graph(
00267                     dotgraph,
00268                     nodename=_conv(node),
00269                     nodelabel=node,
00270                     shape="ellipse",
00271                     url=node + " (WONKY)",
00272                     color="orange")
00273             else:
00274                 dotcode_factory.add_node_to_graph(
00275                     dotgraph,
00276                     nodename=_conv(node),
00277                     nodelabel=node,
00278                     shape="ellipse",
00279                     url=node + " (UNKNOWN)",
00280                     color="red")
00281         else:
00282             dotcode_factory.add_node_to_graph(
00283                 dotgraph,
00284                 nodename=_conv(node),
00285                 nodelabel=node,
00286                 shape='ellipse',
00287                 url=node)
00288 
00289     def _add_topic_node(self, node, dotcode_factory, dotgraph, quiet):
00290         label = rosgraph.impl.graph.node_topic(node)
00291         dotcode_factory.add_node_to_graph(
00292             dotgraph,
00293             nodename=_conv(node),
00294             nodelabel=label,
00295             shape='box',
00296             url="topic:%s" % label)
00297 
00298     def _add_topic_node_group(self, node, dotcode_factory, dotgraph, quiet):
00299         label = rosgraph.impl.graph.node_topic(node)
00300         dotcode_factory.add_node_to_graph(
00301             dotgraph,
00302             nodename=_conv(node),
00303             nodelabel=label,
00304             shape='box3d',
00305             url='topic:%s' % label)
00306 
00307     def _quiet_filter(self, name):
00308         # ignore viewers
00309         for n in QUIET_NAMES:
00310             if n in name:
00311                 return False
00312         return True
00313 
00314     def quiet_filter_topic_edge(self, edge):
00315         for quiet_label in ['/time', '/clock', '/rosout', '/statistics']:
00316             if quiet_label == edge.label:
00317                 return False
00318         return self._quiet_filter(edge.start) and self._quiet_filter(edge.end)
00319 
00320     def generate_namespaces(self, graph, graph_mode, quiet=False):
00321         """
00322         Determine the namespaces of the nodes being displayed
00323         """
00324         namespaces = []
00325         if graph_mode == NODE_NODE_GRAPH:
00326             nodes = graph.nn_nodes
00327             if quiet:
00328                 nodes = [n for n in nodes if n not in QUIET_NAMES]
00329             namespaces = list(set([roslib.names.namespace(n) for n in nodes]))
00330 
00331         elif graph_mode == NODE_TOPIC_GRAPH or \
00332                 graph_mode == NODE_TOPIC_ALL_GRAPH:
00333             nn_nodes = graph.nn_nodes
00334             nt_nodes = graph.nt_nodes
00335             if quiet:
00336                 nn_nodes = [n for n in nn_nodes if n not in QUIET_NAMES]
00337                 nt_nodes = [n for n in nt_nodes if n not in QUIET_NAMES]
00338             if nn_nodes or nt_nodes:
00339                 namespaces = [roslib.names.namespace(n) for n in nn_nodes]
00340             # an annoyance with the rosgraph library is that it
00341             # prepends a space to topic names as they have to have
00342             # different graph node namees from nodes. we have to strip here
00343             namespaces.extend([roslib.names.namespace(n[1:]) for n in nt_nodes])
00344 
00345         return list(set(namespaces))
00346 
00347     def _filter_orphaned_edges(self, edges, nodes):
00348         nodenames = [unicode(n).strip() for n in nodes]
00349         # currently using and rule as the or rule generates orphan nodes with the current logic
00350         return [e for e in edges if e.start.strip() in nodenames and e.end.strip() in nodenames]
00351 
00352     def _filter_orphaned_topics(self, nt_nodes, edges):
00353         '''remove topic graphnodes without connected ROS nodes'''
00354         removal_nodes = []
00355         for n in nt_nodes:
00356             keep = False
00357             for e in edges:
00358                 if e.start.strip() == unicode(n).strip() or e.end.strip() == unicode(n).strip():
00359                     keep = True
00360                     break
00361             if not keep:
00362                 removal_nodes.append(n)
00363         for n in removal_nodes:
00364             nt_nodes.remove(n)
00365         return nt_nodes
00366 
00367     def _split_filter_string(self, ns_filter):
00368         '''splits a string after each comma, and treats tokens with leading dash as exclusions.
00369         Adds .* as inclusion if no other inclusion option was given'''
00370         includes = []
00371         excludes = []
00372         for name in ns_filter.split(','):
00373             if name.strip().startswith('-'):
00374                 excludes.append(name.strip()[1:])
00375             else:
00376                 includes.append(name.strip())
00377         if includes == [] or includes == ['/'] or includes == ['']:
00378             includes = ['.*']
00379         return includes, excludes
00380 
00381     def _get_node_edge_map(self, edges):
00382         '''
00383         returns a dict mapping node name to edge objects partitioned in incoming and outgoing edges
00384         '''
00385         node_connections = {}
00386         for edge in edges:
00387             if edge.start not in node_connections:
00388                 node_connections[edge.start] = NodeConnections()
00389             if edge.end not in node_connections:
00390                 node_connections[edge.end] = NodeConnections()
00391             node_connections[edge.start].outgoing.append(edge)
00392             node_connections[edge.end].incoming.append(edge)
00393         return node_connections
00394 
00395     def _filter_leaf_topics(
00396             self,
00397             nodes_in,
00398             edges_in,
00399             node_connections,
00400             hide_single_connection_topics,
00401             hide_dead_end_topics):
00402         '''
00403         removes certain ending topic nodes and their edges from list of nodes and edges
00404 
00405         @param hide_single_connection_topics:
00406             if true removes topics that are only published/subscribed by one node
00407         @param hide_dead_end_topics: if true removes topics having only publishers
00408         '''
00409         if not hide_dead_end_topics and not hide_single_connection_topics:
00410             return nodes_in, edges_in
00411         # do not manipulate incoming structures
00412         nodes = copy.copy(nodes_in)
00413         edges = copy.copy(edges_in)
00414         removal_nodes = []
00415         for n in nodes:
00416             if n in node_connections:
00417                 node_edges = []
00418                 has_out_edges = False
00419                 node_edges.extend(node_connections[n].outgoing)
00420                 if len(node_connections[n].outgoing) > 0:
00421                     has_out_edges = True
00422                 node_edges.extend(node_connections[n].incoming)
00423                 if (hide_single_connection_topics and len(node_edges) < 2) or \
00424                         (hide_dead_end_topics and not has_out_edges):
00425                     removal_nodes.append(n)
00426                     for e in node_edges:
00427                         if e in edges:
00428                             edges.remove(e)
00429         for n in removal_nodes:
00430             nodes.remove(n)
00431         return nodes, edges
00432 
00433     def _accumulate_action_topics(self, nodes_in, edges_in, node_connections):
00434         '''takes topic nodes, edges and node connections.
00435         Returns topic nodes where action topics have been removed,
00436         edges where the edges to action topics have been removed, and
00437         a map with the connection to each virtual action topic node'''
00438         removal_nodes = []
00439         action_nodes = {}
00440         # do not manipulate incoming structures
00441         nodes = copy.copy(nodes_in)
00442         edges = copy.copy(edges_in)
00443         for n in nodes:
00444             if unicode(n).endswith('/feedback'):
00445                 prefix = unicode(n)[:-len('/feedback')].strip()
00446                 action_topic_nodes = []
00447                 action_topic_edges_out = list()
00448                 action_topic_edges_in = list()
00449                 for suffix in ['/status', '/result', '/goal', '/cancel', '/feedback']:
00450                     for n2 in nodes:
00451                         if unicode(n2).strip() == prefix + suffix:
00452                             action_topic_nodes.append(n2)
00453                             if n2 in node_connections:
00454                                 action_topic_edges_out.extend(node_connections[n2].outgoing)
00455                                 action_topic_edges_in.extend(node_connections[n2].incoming)
00456                 if len(action_topic_nodes) == 5:
00457                     # found action
00458                     removal_nodes.extend(action_topic_nodes)
00459                     for e in action_topic_edges_out:
00460                         if e in edges:
00461                             edges.remove(e)
00462                     for e in action_topic_edges_in:
00463                         if e in edges:
00464                             edges.remove(e)
00465                     action_nodes[prefix] = {'topics': action_topic_nodes,
00466                                             'outgoing': action_topic_edges_out,
00467                                             'incoming': action_topic_edges_in}
00468         for n in removal_nodes:
00469             nodes.remove(n)
00470         return nodes, edges, action_nodes
00471 
00472     def _populate_node_graph(
00473             self,
00474             cluster_namespaces_level,
00475             node_list,
00476             dotcode_factory,
00477             dotgraph,
00478             rank,
00479             orientation,
00480             simplify):
00481         namespace_clusters = {}
00482         if cluster_namespaces_level > 0:
00483             for node in node_list:
00484                 if unicode(node.strip()).count('/') > 2:
00485                     for i in range(
00486                             2, min(2 + cluster_namespaces_level, len(node.strip().split('/')))):
00487                         namespace = '/'.join(node.strip().split('/')[:i])
00488                         parent_namespace = '/'.join(node.strip().split('/')[:i - 1])
00489                         if namespace not in namespace_clusters:
00490                             if parent_namespace == '':
00491                                 namespace_clusters[namespace] = \
00492                                     dotcode_factory.add_subgraph_to_graph(
00493                                         dotgraph,
00494                                         namespace,
00495                                         rank=rank,
00496                                         rankdir=orientation,
00497                                         simplify=simplify)
00498                             elif parent_namespace in namespace_clusters:
00499                                 namespace_clusters[namespace] = \
00500                                     dotcode_factory.add_subgraph_to_graph(
00501                                         namespace_clusters[parent_namespace],
00502                                         namespace,
00503                                         rank=rank,
00504                                         rankdir=orientation,
00505                                         simplify=simplify)
00506                 elif unicode(node.strip()).count('/') == 2:
00507                     namespace = '/'.join(node.strip().split('/')[0:2])
00508                     if namespace not in namespace_clusters:
00509                         namespace_clusters[namespace] = dotcode_factory.add_subgraph_to_graph(
00510                             dotgraph,
00511                             namespace,
00512                             rank=rank,
00513                             rankdir=orientation,
00514                             simplify=simplify)
00515         return namespace_clusters
00516 
00517     def _group_tf_nodes(self, nodes_in, edges_in, node_connections):
00518         '''takes topic nodes, edges and node connections.
00519         Returns topic nodes where tf topics have been removed,
00520         edges where the edges to tf topics have been removed, and
00521         a map with all the connections to the resulting tf group node'''
00522         removal_nodes = []
00523         tf_topic_edges_in = []
00524         tf_topic_edges_out = []
00525         # do not manipulate incoming structures
00526         nodes = copy.copy(nodes_in)
00527         edges = copy.copy(edges_in)
00528         for n in nodes:
00529             if unicode(n).strip() in ['/tf', '/tf_static']:
00530                 tf_topic_edges_in.extend(
00531                     [x for x in node_connections[n].incoming if x in edges and x.end in nodes])
00532                 tf_topic_edges_out.extend(
00533                     [x for x in node_connections[n].outgoing if x in edges and x.start in nodes])
00534                 removal_nodes.append(n)
00535 
00536                 for e in tf_topic_edges_out:
00537                     if e in edges:
00538                         edges.remove(e)
00539                 for e in tf_topic_edges_in:
00540                     if e in edges:
00541                         edges.remove(e)
00542         for n in removal_nodes:
00543             if n in nodes:
00544                 nodes.remove(n)
00545         if not tf_topic_edges_in and not tf_topic_edges_out:
00546             return nodes, edges, None
00547 
00548         return nodes, edges, {'outgoing': tf_topic_edges_out, 'incoming': tf_topic_edges_in}
00549 
00550     def _accumulate_image_topics(self, nodes_in, edges_in, node_connections):
00551         '''takes topic nodes, edges and node connections.
00552         Returns topic nodes where image topics have been removed,
00553         edges where the edges to image topics have been removed, and
00554         a map with the connection to each virtual image topic node'''
00555         removal_nodes = []
00556         image_nodes = {}
00557         # do not manipulate incoming structures
00558         nodes = copy.copy(nodes_in)
00559         edges = copy.copy(edges_in)
00560         for n in nodes:
00561             if unicode(n).endswith('/compressed'):
00562                 prefix = unicode(n)[:-len('/compressed')].strip()
00563                 image_topic_nodes = []
00564                 image_topic_edges_out = list()
00565                 image_topic_edges_in = list()
00566                 for suffix in ['/compressed', '/compressedDepth', '/theora', '']:
00567                     for n2 in nodes:
00568                         if unicode(n2).strip() == prefix + suffix:
00569                             image_topic_nodes.append(n2)
00570                             if n2 in node_connections:
00571                                 image_topic_edges_out.extend(node_connections[n2].outgoing)
00572                                 image_topic_edges_in.extend(node_connections[n2].incoming)
00573                 if len(image_topic_nodes) >= 3:
00574                     # found action
00575                     removal_nodes.extend(image_topic_nodes)
00576                     for e in image_topic_edges_out:
00577                         if e in edges:
00578                             edges.remove(e)
00579                     for e in image_topic_edges_in:
00580                         if e in edges:
00581                             edges.remove(e)
00582                     image_nodes[prefix] = {'topics': image_topic_nodes,
00583                                            'outgoing': image_topic_edges_out,
00584                                            'incoming': image_topic_edges_in}
00585         for n in removal_nodes:
00586             nodes.remove(n)
00587         return nodes, edges, image_nodes
00588 
00589     def _filter_hidden_topics(
00590         self,
00591         nodes_in,
00592         edges_in,
00593         node_connections,
00594         hide_tf_nodes,
00595             hide_dynamic_reconfigure):
00596         if not hide_tf_nodes and not hide_dynamic_reconfigure:
00597             return nodes_in, edges_in
00598         # do not manipulate incoming structures
00599         nodes = copy.copy(nodes_in)
00600         edges = copy.copy(edges_in)
00601         removal_nodes = []
00602         for n in nodes:
00603             if hide_dynamic_reconfigure and unicode(n).endswith('/parameter_updates'):
00604                 prefix = unicode(n)[:-len('/parameter_updates')].strip()
00605                 dynamic_reconfigure_topic_nodes = []
00606                 for suffix in ['/parameter_updates', '/parameter_descriptions']:
00607                     for n2 in nodes:
00608                         if unicode(n2).strip() == prefix + suffix:
00609                             dynamic_reconfigure_topic_nodes.append(n2)
00610                 if len(dynamic_reconfigure_topic_nodes) == 2:
00611                     for n1 in dynamic_reconfigure_topic_nodes:
00612                         if n1 in node_connections:
00613                             for e in node_connections[n1].outgoing + node_connections[n1].incoming:
00614                                 if e in edges:
00615                                     edges.remove(e)
00616                         removal_nodes.append(n1)
00617                     continue
00618             if hide_tf_nodes and unicode(n).strip() in ['/tf', '/tf_static']:
00619                 if n in node_connections:
00620                     for e in node_connections[n].outgoing + node_connections[n].incoming:
00621                         if e in edges:
00622                             edges.remove(e)
00623                 removal_nodes.append(n)
00624                 continue
00625         for n in removal_nodes:
00626             if n in nodes:
00627                 nodes.remove(n)
00628         return nodes, edges
00629 
00630     def generate_dotgraph(
00631         self,
00632         rosgraphinst,
00633         ns_filter,
00634         topic_filter,
00635         graph_mode,
00636         dotcode_factory,
00637         hide_single_connection_topics=False,
00638         hide_dead_end_topics=False,
00639         cluster_namespaces_level=0,
00640         accumulate_actions=True,
00641         orientation='LR',
00642         rank='same',  # None, same, min, max, source, sink
00643         ranksep=0.2,  # vertical distance between layers
00644         rankdir='TB',  # direction of layout (TB top > bottom, LR left > right)
00645         simplify=True,  # remove double edges
00646         quiet=False,
00647         unreachable=False,
00648         group_tf_nodes=False,
00649         hide_tf_nodes=False,
00650         group_image_nodes=False,
00651             hide_dynamic_reconfigure=False):
00652         """
00653         See generate_dotcode
00654         """
00655         includes, excludes = self._split_filter_string(ns_filter)
00656         topic_includes, topic_excludes = self._split_filter_string(topic_filter)
00657 
00658         nn_nodes = []
00659         nt_nodes = []
00660         # create the node definitions
00661         if graph_mode == NODE_NODE_GRAPH:
00662             nn_nodes = rosgraphinst.nn_nodes
00663             nn_nodes = \
00664                 [n for n in nn_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
00665             edges = rosgraphinst.nn_edges
00666             edges = \
00667                 [e for e in edges if matches_any(
00668                     e.label, topic_includes) and not matches_any(e.label, topic_excludes)]
00669 
00670         elif graph_mode == NODE_TOPIC_GRAPH or \
00671                 graph_mode == NODE_TOPIC_ALL_GRAPH:
00672             nn_nodes = rosgraphinst.nn_nodes
00673             nt_nodes = rosgraphinst.nt_nodes
00674             nn_nodes = \
00675                 [n for n in nn_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
00676             nt_nodes = \
00677                 [n for n in nt_nodes if matches_any(n, topic_includes) and
00678                     not matches_any(n, topic_excludes)]
00679 
00680             # create the edge definitions, unwrap EdgeList objects into python lists
00681             if graph_mode == NODE_TOPIC_GRAPH:
00682                 edges = [e for e in rosgraphinst.nt_edges]
00683             else:
00684                 edges = [e for e in rosgraphinst.nt_all_edges]
00685 
00686         if quiet:
00687             nn_nodes = list(filter(self._quiet_filter, nn_nodes))
00688             nt_nodes = list(filter(self._quiet_filter, nt_nodes))
00689             if graph_mode == NODE_NODE_GRAPH:
00690                 edges = list(filter(self.quiet_filter_topic_edge, edges))
00691 
00692         # for accumulating actions topics
00693         action_nodes = {}
00694         # for accumulating image topics
00695         image_nodes = {}
00696         # for accumulating tf node connections
00697         tf_connections = None
00698 
00699         if graph_mode != NODE_NODE_GRAPH and (hide_single_connection_topics or
00700                                               hide_dead_end_topics or accumulate_actions or
00701                                               group_tf_nodes or hide_tf_nodes or
00702                                               group_image_nodes or hide_dynamic_reconfigure):
00703             # maps outgoing and incoming edges to nodes
00704             node_connections = self._get_node_edge_map(edges)
00705 
00706             nt_nodes, edges = self._filter_leaf_topics(
00707                 nt_nodes,
00708                 edges,
00709                 node_connections,
00710                 hide_single_connection_topics,
00711                 hide_dead_end_topics)
00712 
00713             nt_nodes, edges = self._filter_hidden_topics(
00714                 nt_nodes,
00715                 edges,
00716                 node_connections,
00717                 hide_tf_nodes,
00718                 hide_dynamic_reconfigure)
00719 
00720             if accumulate_actions:
00721                 nt_nodes, edges, action_nodes = self._accumulate_action_topics(
00722                     nt_nodes, edges, node_connections)
00723             if group_image_nodes:
00724                 nt_nodes, edges, image_nodes = self._accumulate_image_topics(
00725                     nt_nodes, edges, node_connections)
00726             if group_tf_nodes and not hide_tf_nodes:
00727                 nt_nodes, edges, tf_connections = self._group_tf_nodes(
00728                     nt_nodes, edges, node_connections)
00729 
00730         edges = self._filter_orphaned_edges(edges, nn_nodes + nt_nodes)
00731         nt_nodes = self._filter_orphaned_topics(nt_nodes, edges)
00732 
00733         # create the graph
00734         # result = "digraph G {\n
00735         # rankdir=%(orientation)s;\n%(nodes_str)s\n%(edges_str)s}\n" % vars()
00736         dotgraph = dotcode_factory.get_graph(
00737             rank=rank,
00738             ranksep=ranksep,
00739             simplify=simplify,
00740             rankdir=orientation)
00741 
00742         ACTION_TOPICS_SUFFIX = '/action_topics'
00743         IMAGE_TOPICS_SUFFIX = '/image_topics'
00744 
00745         node_list = (nt_nodes or []) + \
00746             [action_prefix + ACTION_TOPICS_SUFFIX for (action_prefix, _) in action_nodes.items()] + \
00747             [image_prefix + IMAGE_TOPICS_SUFFIX for (image_prefix, _) in image_nodes.items()] + \
00748             nn_nodes if nn_nodes is not None else []
00749 
00750         namespace_clusters = self._populate_node_graph(
00751             cluster_namespaces_level,
00752             node_list,
00753             dotcode_factory,
00754             dotgraph,
00755             rank,
00756             orientation,
00757             simplify)
00758 
00759         for n in nt_nodes or []:
00760             # cluster topics with same namespace
00761             if cluster_namespaces_level > 0 and \
00762                     unicode(n).strip().count('/') > 1 and \
00763                     len(n.strip().split('/')[1]) > 0:
00764                 if n.count('/') <= cluster_namespaces_level:
00765                     namespace = unicode('/'.join(n.strip().split('/')[:-1]))
00766                 else:
00767                     namespace = '/'.join(n.strip().split('/')[:cluster_namespaces_level + 1])
00768                 self._add_topic_node(
00769                     n, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace], quiet=quiet)
00770             else:
00771                 self._add_topic_node(
00772                     n, dotcode_factory=dotcode_factory, dotgraph=dotgraph, quiet=quiet)
00773 
00774         for n in [action_prefix + ACTION_TOPICS_SUFFIX for (action_prefix, _) in action_nodes.items()] + \
00775                 [image_prefix + IMAGE_TOPICS_SUFFIX for (image_prefix, _) in image_nodes.items()]:
00776             # cluster topics with same namespace
00777             if cluster_namespaces_level > 0 and \
00778                     unicode(n).strip().count('/') > 1 and \
00779                     len(unicode(n).strip().split('/')[1]) > 0:
00780                 if n.strip().count('/') <= cluster_namespaces_level:
00781                     namespace = unicode('/'.join(n.strip().split('/')[:-1]))
00782                 else:
00783                     namespace = '/'.join(n.strip().split('/')[:cluster_namespaces_level + 1])
00784                 self._add_topic_node_group(
00785                     'n' + n, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace], quiet=quiet)
00786             else:
00787                 self._add_topic_node_group(
00788                     'n' + n, dotcode_factory=dotcode_factory, dotgraph=dotgraph, quiet=quiet)
00789 
00790         if tf_connections != None:
00791             # render tf nodes as a single node
00792             self._add_topic_node_group(
00793                 'n/tf', dotcode_factory=dotcode_factory, dotgraph=dotgraph, quiet=quiet)
00794             for out_edge in tf_connections.get('outgoing', []):
00795                 dotcode_factory.add_edge_to_graph(dotgraph, _conv('n/tf'), _conv(out_edge.end))
00796             for in_edge in tf_connections.get('incoming', []):
00797                 dotcode_factory.add_edge_to_graph(dotgraph, _conv(in_edge.start), _conv('n/tf'))
00798 
00799         # for ROS node, if we have created a namespace clusters for
00800         # one of its peer topics, drop it into that cluster
00801         for n in nn_nodes or []:
00802             if cluster_namespaces_level > 0 and \
00803                     n.strip().count('/') > 1 and \
00804                     len(n.strip().split('/')[1]) > 0:
00805                 if n.count('/') <= cluster_namespaces_level:
00806                     namespace = unicode('/'.join(n.strip().split('/')[:-1]))
00807                 else:
00808                     namespace = '/'.join(n.strip().split('/')[:cluster_namespaces_level + 1])
00809                 self._add_node(
00810                     n,
00811                     rosgraphinst=rosgraphinst,
00812                     dotcode_factory=dotcode_factory,
00813                     dotgraph=namespace_clusters[namespace],
00814                     unreachable=unreachable)
00815             else:
00816                 self._add_node(
00817                     n,
00818                     rosgraphinst=rosgraphinst,
00819                     dotcode_factory=dotcode_factory,
00820                     dotgraph=dotgraph,
00821                     unreachable=unreachable)
00822 
00823         for e in edges:
00824             self._add_edge(
00825                 e, dotcode_factory, dotgraph=dotgraph, is_topic=(graph_mode == NODE_NODE_GRAPH))
00826 
00827         for (action_prefix, node_connections) in action_nodes.items():
00828             for out_edge in node_connections.get('outgoing', []):
00829                 dotcode_factory.add_edge_to_graph(
00830                     dotgraph,
00831                     _conv('n' + action_prefix + ACTION_TOPICS_SUFFIX),
00832                     _conv(out_edge.end))
00833             for in_edge in node_connections.get('incoming', []):
00834                 dotcode_factory.add_edge_to_graph(
00835                     dotgraph,
00836                     _conv(in_edge.start),
00837                     _conv('n' + action_prefix + ACTION_TOPICS_SUFFIX))
00838         for (image_prefix, node_connections) in image_nodes.items():
00839             for out_edge in node_connections.get('outgoing', []):
00840                 dotcode_factory.add_edge_to_graph(
00841                     dotgraph,
00842                     _conv('n' + image_prefix + IMAGE_TOPICS_SUFFIX),
00843                     _conv(out_edge.end))
00844             for in_edge in node_connections.get('incoming', []):
00845                 dotcode_factory.add_edge_to_graph(
00846                     dotgraph,
00847                     _conv(in_edge.start),
00848                     _conv('n' + image_prefix + IMAGE_TOPICS_SUFFIX))
00849 
00850         return dotgraph
00851 
00852     def generate_dotcode(
00853         self,
00854         rosgraphinst,
00855         ns_filter,
00856         topic_filter,
00857         graph_mode,
00858         dotcode_factory,
00859         hide_single_connection_topics=False,
00860         hide_dead_end_topics=False,
00861         cluster_namespaces_level=0,
00862         accumulate_actions=True,
00863         orientation='LR',
00864         rank='same',  # None, same, min, max, source, sink
00865         ranksep=0.2,  # vertical distance between layers
00866         rankdir='TB',  # direction of layout (TB top > bottom, LR left > right)
00867         simplify=True,  # remove double edges
00868         quiet=False,
00869         unreachable=False,
00870         hide_tf_nodes=False,
00871         group_tf_nodes=False,
00872         group_image_nodes=False,
00873             hide_dynamic_reconfigure=False):
00874         """
00875         @param rosgraphinst: RosGraph instance
00876         @param ns_filter: nodename filter
00877         @type  ns_filter: string
00878         @param topic_filter: topicname filter
00879         @type  ns_filter: string
00880         @param graph_mode str: NODE_NODE_GRAPH | NODE_TOPIC_GRAPH | NODE_TOPIC_ALL_GRAPH
00881         @type  graph_mode: str
00882         @param orientation: rankdir value (see ORIENTATIONS dict)
00883         @type  dotcode_factory: object
00884         @param dotcode_factory: abstract factory manipulating dot language objects
00885         @param hide_single_connection_topics: if true remove topics with just one connection
00886         @param hide_dead_end_topics: if true remove topics with publishers only
00887         @param cluster_namespaces_level: if > 0 places box around members of same namespace
00888                (TODO: multiple namespace layers)
00889         @param accumulate_actions: if true each 5 action topic graph nodes are shown as single graph node
00890         @return: dotcode generated from graph singleton
00891         @rtype: str
00892         """
00893         dotgraph = self.generate_dotgraph(
00894             rosgraphinst=rosgraphinst,
00895             ns_filter=ns_filter,
00896             topic_filter=topic_filter,
00897             graph_mode=graph_mode,
00898             dotcode_factory=dotcode_factory,
00899             hide_single_connection_topics=hide_single_connection_topics,
00900             hide_dead_end_topics=hide_dead_end_topics,
00901             cluster_namespaces_level=cluster_namespaces_level,
00902             accumulate_actions=accumulate_actions,
00903             orientation=orientation,
00904             rank=rank,
00905             ranksep=ranksep,
00906             rankdir=rankdir,
00907             simplify=simplify,
00908             quiet=quiet,
00909             unreachable=unreachable,
00910             hide_tf_nodes=hide_tf_nodes,
00911             group_tf_nodes=group_tf_nodes,
00912             group_image_nodes=group_image_nodes,
00913             hide_dynamic_reconfigure=hide_dynamic_reconfigure)
00914         dotcode = dotcode_factory.create_dot(dotgraph)
00915         return dotcode


rqt_graph
Author(s): Dirk Thomas
autogenerated on Thu Jun 6 2019 17:35:26