$search
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 # Revision $Id$ 00034 00035 import roslib.names 00036 import rosgraph.impl.graph 00037 00038 ORIENTATIONS = ['LR', 'TB', 'RL', 'BT'] 00039 00040 INIT_DOTCODE = """ 00041 digraph G { initializing [label="initializing..."]; } 00042 """ 00043 00044 # node/node connectivity 00045 NODE_NODE_GRAPH = "node_node" 00046 # node/topic connections where an actual network connection exists 00047 NODE_TOPIC_GRAPH = "node_topic" 00048 # all node/topic connections, even if no actual network connection 00049 NODE_TOPIC_ALL_GRAPH = "node_topic_all" 00050 00051 import urllib 00052 def safe_dotcode_name(name): 00053 """ 00054 encode the name for dotcode symbol-safe syntax 00055 """ 00056 # not the best solution, but unsafe names shouldn't be coming through much 00057 ret = urllib.quote(name) 00058 ret = ret.replace('/', '_') 00059 ret = ret.replace('%', '_') 00060 ret = ret.replace('-', '_') 00061 return ret 00062 00063 def _edge_to_dot(e): 00064 if e.label: 00065 return ' %s->%s [label="%s"]'%(safe_dotcode_name(e.start), safe_dotcode_name(e.end), e.label) 00066 else: 00067 return ' %s->%s'%(safe_dotcode_name(e.start), safe_dotcode_name(e.end)) 00068 00069 def _generate_node_dotcode(node, g, quiet): 00070 if node in g.bad_nodes: 00071 bn = g.bad_nodes[node] 00072 if bn.type == rosgraph.impl.graph.BadNode.DEAD: 00073 return ' %s [color="red", shape="doublecircle", label="%s", URL="node:%s"];'%( 00074 safe_dotcode_name(node), node, node) 00075 else: 00076 return ' %s [color="orange", shape="doublecircle", label="%s", URL="node:%s"];'%( 00077 safe_dotcode_name(node), node, node, node) 00078 else: 00079 return ' %s [label="%s", URL="node:%s"];'%(safe_dotcode_name(node), node, node) 00080 00081 QUIET_NAMES = ['/diag_agg', '/runtime_logger', '/pr2_dashboard', '/rviz', '/rosout', '/cpu_monitor', '/monitor','/hd_monitor', '/rxloggerlevel', '/clock'] 00082 def _quiet_filter(name): 00083 # ignore viewers 00084 for n in QUIET_NAMES: 00085 if n in name: 00086 return False 00087 return True 00088 00089 def _quiet_filter_edge(edge): 00090 for quiet_label in ['/time', '/clock', '/rosout']: 00091 if quiet_label == edge.label: 00092 return False 00093 return _quiet_filter(edge.start) and _quiet_filter(edge.end) 00094 00095 def generate_namespaces(g, graph_mode, quiet=False): 00096 """ 00097 Determine the namespaces of the nodes being displayed 00098 """ 00099 namespaces = [] 00100 if graph_mode == NODE_NODE_GRAPH: 00101 nodes = g.nn_nodes 00102 if quiet: 00103 nodes = [n for n in nodes if not n in QUIET_NAMES] 00104 namespaces = list(set([roslib.names.namespace(n) for n in nodes])) 00105 00106 elif graph_mode == NODE_TOPIC_GRAPH or \ 00107 graph_mode == NODE_TOPIC_ALL_GRAPH: 00108 nn_nodes = g.nn_nodes 00109 nt_nodes = g.nt_nodes 00110 if quiet: 00111 nn_nodes = [n for n in nn_nodes if not n in QUIET_NAMES] 00112 nt_nodes = [n for n in nt_nodes if not n in QUIET_NAMES] 00113 if nn_nodes or nt_nodes: 00114 namespaces = [roslib.names.namespace(n) for n in nn_nodes] 00115 # an annoyance with the rosgraph library is that it 00116 # prepends a space to topic names as they have to have 00117 # different graph node namees from nodes. we have to strip here 00118 namespaces.extend([roslib.names.namespace(n[1:]) for n in nt_nodes]) 00119 00120 return list(set(namespaces)) 00121 00122 def _filter_edges(edges, nodes): 00123 # currently using and rule as the or rule generates orphan nodes with the current logic 00124 return [e for e in edges if e.start in nodes and e.end in nodes] 00125 00126 def generate_dotcode(g, ns_filter, graph_mode, orientation, quiet=False): 00127 """ 00128 @param g: Graph instance 00129 @param ns_filter: namespace filter (must be canonicalized with trailing '/') 00130 @type ns_filter: string 00131 @param graph_mode str: NODE_NODE_GRAPH | NODE_TOPIC_GRAPH | NODE_TOPIC_ALL_GRAPH 00132 @type graph_mode: str 00133 @param orientation: rankdir value (see ORIENTATIONS dict) 00134 @return: dotcode generated from graph singleton 00135 @rtype: str 00136 """ 00137 #print "generate_dotcode", graph_mode 00138 if ns_filter: 00139 name_filter = ns_filter[:-1] 00140 00141 # create the node definitions 00142 if graph_mode == NODE_NODE_GRAPH: 00143 nodes = g.nn_nodes 00144 if quiet: 00145 nodes = [n for n in nodes if not n in QUIET_NAMES] 00146 if ns_filter and ns_filter != '/': 00147 nodes = [n for n in nodes if n.startswith(ns_filter) or n == name_filter] 00148 if nodes: 00149 nodes_str = '\n'.join([_generate_node_dotcode(n, g, quiet) for n in nodes]) 00150 else: 00151 nodes_str = ' empty;' 00152 00153 elif graph_mode == NODE_TOPIC_GRAPH or \ 00154 graph_mode == NODE_TOPIC_ALL_GRAPH: 00155 nn_nodes = g.nn_nodes 00156 nt_nodes = g.nt_nodes 00157 if quiet: 00158 nn_nodes = [n for n in nn_nodes if not n in QUIET_NAMES] 00159 nt_nodes = [n for n in nt_nodes if not n in QUIET_NAMES] 00160 if ns_filter and ns_filter != '/': 00161 nn_nodes = [n for n in nn_nodes if n.startswith(ns_filter) or n == name_filter] 00162 nt_nodes = [n for n in nt_nodes if n[1:].startswith(ns_filter) or n[1:] == name_filter] 00163 00164 if nn_nodes or nt_nodes: 00165 nodes_str = '\n'.join([_generate_node_dotcode(n, g, quiet) for n in nn_nodes]) 00166 nodes_str += '\n'.join([' %s [shape=box,label="%s",URL="topic:%s"];'%( 00167 safe_dotcode_name(n), rosgraph.impl.graph.node_topic(n), rosgraph.impl.graph.node_topic(n)) for n in nt_nodes]) 00168 else: 00169 nodes_str = ' empty;' 00170 nodes = list(nn_nodes) + list(nt_nodes) 00171 00172 # create the edge definitions 00173 if graph_mode == NODE_NODE_GRAPH: 00174 edges = g.nn_edges 00175 elif graph_mode == NODE_TOPIC_GRAPH: 00176 edges = g.nt_edges 00177 else: 00178 edges = g.nt_all_edges 00179 if quiet: 00180 edges = filter(_quiet_filter_edge, edges) 00181 00182 edges = _filter_edges(edges, nodes) 00183 edges_str = '\n'.join([_edge_to_dot(e) for e in edges]) 00184 return "digraph G {\n rankdir=%(orientation)s;\n%(nodes_str)s\n%(edges_str)s}\n"%vars() 00185