graph.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   This code does not effect the runtime of gateways at all - it is used for
00008   debugging and monitoring purposes only.
00009 '''
00010 ##############################################################################
00011 # Imports
00012 ##############################################################################
00013 
00014 import roslib
00015 roslib.load_manifest('rocon_gateway')
00016 import rospy
00017 import gateway_msgs.srv
00018 from master_api import LocalMaster
00019 import rosgraph
00020 from rosgraph.impl.graph import Edge, EdgeList
00021 
00022 ##############################################################################
00023 # Graph
00024 ##############################################################################
00025 
00026 
00027 class Graph(object):
00028     '''
00029     Utility class for polling statistics from a running gateway-hub network.
00030     '''
00031 
00032     def __init__(self):
00033         '''
00034         Creates the polling topics necessary for updating statistics
00035         about the running gateway-hub network.
00036         '''
00037         self._last_update = 0
00038         self._gateway_namespace = None
00039         self._local_gateway = None
00040         self._remote_gateways = None
00041         self.gateway_nodes = []  # Gateway nodes
00042         self.flipped_nodes = []  # Flip connection nodes (i.e. topic name)
00043         self.pulled_nodes = []
00044         self.pulled_edges = []  # Gateway-Topic edges
00045         self.gateway_edges = []  # Gateway-Gateway edges
00046         self.flipped_edges = []  # All unconnected node-topics or topic-nodes
00047 
00048         # Rubbish to clear out once rocon_gateway_graph is integrated
00049         self.bad_nodes = []
00050 
00051         if self._resolve_gateway_namespace():
00052             self.configure()
00053 
00054     def configure(self):
00055         self._gateway_info = rospy.ServiceProxy(self.gateway_namespace + '/gateway_info', gateway_msgs.srv.GatewayInfo)
00056         self._remote_gateway_info = rospy.ServiceProxy(self.gateway_namespace + '/remote_gateway_info', gateway_msgs.srv.RemoteGatewayInfo)
00057 
00058     def local_gateway_name(self):
00059         if self._local_gateway:
00060             return self._local_gateway.name
00061         else:
00062             return ''
00063 
00064     def update(self):
00065         if not self._resolve_gateway_namespace():
00066             return
00067         req = gateway_msgs.srv.GatewayInfoRequest()
00068         self._local_gateway = self._gateway_info(req)
00069         req = gateway_msgs.srv.RemoteGatewayInfoRequest()
00070         req.gateways = []
00071         self._remote_gateways = self._remote_gateway_info(req).gateways
00072         self._last_update = rospy.get_rostime()
00073         # Gateways
00074         self.gateway_nodes.append(self._local_gateway.name)
00075         self.gateway_nodes.extend([remote_gateway.name for remote_gateway in self._remote_gateways])
00076         # Edges
00077         self.pulled_edges = EdgeList()
00078         self.gateway_edges = EdgeList()
00079         self.pulled_edges = EdgeList()
00080         self.flipped_edges = EdgeList()
00081         # Check local gateway
00082         for remote_rule in self._local_gateway.flipped_connections:
00083             self.gateway_edges.add(Edge(self._local_gateway.name, remote_rule.gateway))
00084             # this adds a bloody magic space, to help disambiguate node names from topic names
00085             connection_id = rosgraph.impl.graph.topic_node(remote_rule.rule.name + '-' + remote_rule.rule.type)
00086             self.flipped_nodes.append(connection_id)
00087             self.flipped_edges.add(Edge(self._local_gateway.name, connection_id))
00088             self.flipped_edges.add(Edge(connection_id, remote_rule.gateway))
00089         for remote_rule in self._local_gateway.pulled_connections:
00090             connection_id = rosgraph.impl.graph.topic_node(remote_rule.rule.name + '-' + remote_rule.rule.type)
00091             self.pulled_nodes.append(connection_id)
00092             self.pulled_edges.add(Edge(self._local_gateway.name, connection_id))
00093             self.pulled_edges.add(Edge(connection_id, remote_rule.gateway))
00094         for rule in self._local_gateway.public_interface:
00095             print "pulled edge: %s->%s" % (self._local_gateway.name, connection_id)
00096             connection_id = rosgraph.impl.graph.topic_node(rule.name + '-' + rule.type)
00097             self.pulled_nodes.append(connection_id)
00098             self.pulled_edges.add(Edge(self._local_gateway.name, connection_id))
00099         # Check remote gateways
00100         # TODO add flipped and pulled here.
00101         for remote_gateway in self._remote_gateways:
00102             for remote_rule in remote_gateway.flipped_interface:
00103                 connection_id = rosgraph.impl.graph.topic_node(remote_rule.rule.name + '-' + remote_rule.rule.type)
00104                 self.flipped_nodes.append(connection_id)
00105                 self.flipped_edges.add(Edge(remote_gateway.name, connection_id))
00106                 self.flipped_edges.add(Edge(connection_id, remote_rule.gateway))
00107                 self.gateway_edges.add(Edge(remote_gateway.name, remote_rule.gateway))
00108             for remote_rule in remote_gateway.pulled_interface:
00109                 connection_id = rosgraph.impl.graph.topic_node(remote_rule.rule.name + '-' + remote_rule.rule.type)
00110                 self.pulled_nodes.append(connection_id)
00111                 self.pulled_edges.add(Edge(remote_rule.gateway, connection_id))
00112                 self.pulled_edges.add(Edge(connection_id, remote_gateway.name))
00113                 self.gateway_edges.add(Edge(remote_gateway.name, remote_rule.gateway))
00114         print "****************** Flipped Nodes ******************"
00115         print self.flipped_nodes
00116         print "****************** Gateway Edges ******************"
00117         print self.gateway_edges
00118 
00119     def _resolve_gateway_namespace(self):
00120         '''
00121           Checks if the gateway namespace was found and if not
00122           attempts to resolve it.
00123         '''
00124         if self._gateway_namespace:
00125             return
00126         master = LocalMaster()
00127         self.gateway_namespace = master.findGatewayNamespace()
00128         if not self.gateway_namespace:
00129             rospy.logerr("Gateway Graph: could not find a local gateway - did you start it?")
00130         return self.gateway_namespace
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rocon_gateway
Author(s): Daniel Stonier, Jihoon Lee,
autogenerated on Tue Jan 15 2013 17:43:24