dotcode.py
Go to the documentation of this file.
00001 #
00002 # License: BSD
00003 #   https://raw.github.com/robotics-in-concert/rocon_qt_gui/license/LICENSE
00004 #
00005 ##############################################################################
00006 # Imports
00007 ##############################################################################
00008 
00009 import rocon_gateway_utils
00010 from rosgraph.impl.graph import Edge
00011 import concert_msgs.msg as concert_msgs
00012 
00013 
00014 ##############################################################################
00015 # Implementation
00016 ##############################################################################
00017 
00018 
00019 class ConductorGraphDotcodeGenerator:
00020 
00021     def __init__(self):
00022         pass
00023 
00024     def _add_edge(self, edge, dotcode_factory, dotgraph):
00025 #         if is_topic:
00026 #             dotcode_factory.add_edge_to_graph(dotgraph, edge.start, edge.end, label=edge.label, url='topic:%s' % edge.label)
00027 #         else:
00028         dotcode_factory.add_edge_to_graph(dotgraph, edge.start, edge.end, label=edge.label)
00029 
00030     def _add_conductor_node(self, dotcode_factory, dotgraph):
00031         '''
00032         The conductor is a special case node, we treat this especially here.
00033         '''
00034         dotcode_factory.add_node_to_graph(dotgraph,
00035                                           nodename="conductor",
00036                                           #nodename=rocon_gateway_utils.gateway_basename(node),
00037                                           #nodelabel=rocon_gateway_utils.gateway_basename(node),
00038                                           shape='ellipse',
00039                                           url="conductor",
00040                                           #url=node
00041                                           color="blue"
00042                                           )
00043 
00044     def _add_node(self, node, dotcode_factory, dotgraph):
00045         '''
00046         A node here is a concert client. We basically add nodes and classify according
00047         to their state in the dotgraph.
00048 
00049         :param node .concert_client.ConcertClient: the concert client to show on the dotgraph
00050         '''
00051         # colour strings defined as per http://qt-project.org/doc/qt-4.8/qcolor.html#setNamedColor
00052         # and http://www.w3.org/TR/SVG/types.html#ColorKeywords
00053         if node.state == concert_msgs.ConcertClientState.PENDING:
00054             node_colour = "magenta"
00055         elif node.state == concert_msgs.ConcertClientState.JOINING:
00056             node_colour = "magenta"
00057         elif node.state == concert_msgs.ConcertClientState.UNINVITED:
00058             node_colour = "midnightblue"
00059         elif node.state == concert_msgs.ConcertClientState.AVAILABLE:
00060             node_colour = "blue"
00061         elif node.state == concert_msgs.ConcertClientState.MISSING:
00062             node_colour = "powderblue"
00063         elif node.state == concert_msgs.ConcertClientState.BLOCKING:
00064             node_colour = "black"
00065         elif node.state == concert_msgs.ConcertClientState.BUSY:
00066             node_colour = "black"
00067         elif node.state == concert_msgs.ConcertClientState.GONE:
00068             node_colour = "black"
00069         elif node.state == concert_msgs.ConcertClientState.BAD:
00070             node_colour = "red"
00071         dotcode_factory.add_node_to_graph(dotgraph,
00072                                           nodename=node.concert_alias,
00073                                           #nodename=rocon_gateway_utils.gateway_basename(node),
00074                                           #nodelabel=rocon_gateway_utils.gateway_basename(node),
00075                                           shape='ellipse',
00076                                           url=rocon_gateway_utils.gateway_basename(node.gateway_name),
00077                                           #url=node,
00078                                           color=node_colour
00079                                           )
00080 
00081     def get_nodes_and_edges(self, conductor_graph_instance):
00082         """
00083         Get all the nodes and edges corresponding to our conductor's graph of concert clients.
00084 
00085         :returns: all the nodes and edges
00086         :rtype: (concert_client.ConcertClient[], rosgraph.impl.graph.Edge[])
00087         """
00088         nodes = conductor_graph_instance.concert_clients.values()
00089         edges = []
00090         important_states = [
00091                         concert_msgs.ConcertClientState.MISSING,
00092                         concert_msgs.ConcertClientState.AVAILABLE
00093                        ]
00094         for node in nodes:
00095             if node.msg.state in important_states:  # and node.msg.conn_stats.gateway_available:
00096                 edges.append(Edge("conductor", node.concert_alias, node.link_type))
00097         return (nodes, edges)
00098 
00099     def generate_dotcode(self,
00100                          conductor_graph_instance,
00101                          dotcode_factory,
00102                          clusters=False,
00103                          uninvited_filter=False,  # not yet used
00104                          orientation='LR',
00105                          rank='same',
00106                          ranksep=0.2,
00107                          rankdir='TB',
00108                          simplify=True,
00109                          ):
00110         """
00111         :param conductor_graph_instance ConductorGraphInfo: all the information behind the graph
00112         :param dotcode_factory: abstract factory manipulating dot language objects
00113         :param clusters bool: whether to show by ip clusters or not
00114         :param uninvited_filter: disable viewing of uninvited clients
00115         :param orientation: rankdir value (see ORIENTATIONS dict)
00116         :param rank str: one of None, same, min, max, source, sink
00117         :param ranksep float: vertical distance between layers
00118         :param rankdir str: direction of layout (TB top > bottom, LR left > right)
00119         :param simplify bool: remove double edges
00120         :returns: dotcode generated from graph singleton
00121         :rtype: str
00122         """
00123         (nodes, edges) = self.get_nodes_and_edges(conductor_graph_instance)
00124         dotgraph = dotcode_factory.get_graph(rank=rank,
00125                                              ranksep=ranksep,
00126                                              simplify=simplify,
00127                                              rankdir=orientation)
00128 
00129         ip_clusters = {}
00130         if conductor_graph_instance.is_conductor:
00131             self._add_conductor_node(dotcode_factory=dotcode_factory, dotgraph=dotgraph)
00132         if nodes is not None:
00133             for node in nodes:
00134                 if clusters:
00135                     if node.ip not in ip_clusters.keys():
00136                         ip_clusters[node.ip] = dotcode_factory.add_subgraph_to_graph(dotgraph, node.ip, rank=rank, rankdir=orientation, simplify=simplify)
00137                     self._add_node(node, dotcode_factory=dotcode_factory, dotgraph=ip_clusters[node.ip])
00138                 else:
00139                     self._add_node(node, dotcode_factory=dotcode_factory, dotgraph=dotgraph)
00140         for e in edges:
00141             self._add_edge(e, dotcode_factory, dotgraph=dotgraph)
00142 
00143         dotcode = dotcode_factory.create_dot(dotgraph)
00144         return dotcode
00145 
00146 class ConductorStateDotcodeGenerator:
00147     '''
00148         Unlike Conductor graph focuses on visualising status of clients, ConductorState focuses on states and transitions.
00149     '''
00150 
00151     def __init__(self, dotcode_factory):
00152         self._dotcode_factory = dotcode_factory
00153         pass
00154 
00155     def generate_dotcode(self, state_transition_table, **kargs):
00156         dotgraph = self.generate_dotgraph(state_transition_table, **kargs)
00157         dotcode = self._dotcode_factory.create_dot(dotgraph)
00158         return dotcode
00159 
00160     def generate_dotgraph(self, state_transition_table, rank='same',ranksep=0.5, rankdir='TB', simplify=True):
00161         nodes, edges = self.get_nodes_and_edges(state_transition_table)
00162         dotgraph = self._dotcode_factory.get_graph(rank=rank, ranksep=ranksep, simplify=simplify, rankdir=rankdir)
00163         self._add_not_in_network_node_and_edge(dotgraph)
00164 
00165         for n in nodes:
00166             self._add_node(dotgraph, n)
00167 
00168         for e in edges:
00169             self._add_edge(dotgraph, e)
00170         return dotgraph
00171 
00172     def get_nodes_and_edges(self, state_transition_table):
00173         nodes = []
00174         edges = []
00175 
00176         for transition, transition_func in state_transition_table.items():
00177             fr, to = transition
00178             nodes.append(fr)
00179             nodes.append(to)
00180 
00181             label = '' if transition_func.__name__ == 'Dummy' else transition_func.__name__
00182         
00183             edges.append(Edge(fr, to, label))
00184 
00185         # make it as unique string list
00186         nodes = list(set(nodes))
00187 
00188         return nodes, edges
00189     
00190     def _add_not_in_network_node_and_edge(self, dotgraph):
00191         start_node_name = "not in network"
00192         self._dotcode_factory.add_node_to_graph(dotgraph, start_node_name, shape='ellipse', color="blue")
00193         self._dotcode_factory.add_edge_to_graph(dotgraph, start_node_name, concert_msgs.ConcertClientState.PENDING, penwidth=0.3)
00194         self._dotcode_factory.add_edge_to_graph(dotgraph, concert_msgs.ConcertClientState.GONE, start_node_name, penwidth=0.3)
00195 
00196 
00197     def _add_node(self, dotgraph, node):
00198         self._dotcode_factory.add_node_to_graph(dotgraph, nodename = node, shape='ellipse')
00199 
00200     def _add_edge(self, dotgraph, edge):
00201         self._dotcode_factory.add_edge_to_graph(dotgraph, edge.start, edge.end, label=edge.label, penwidth=0.3)


concert_utilities
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 18:17:52