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


rocon_gateway_graph
Author(s): Daniel Stonier
autogenerated on Tue Jan 15 2013 17:43:51