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/license/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 rospy
00015 import gateway_msgs.srv as gateway_srvs
00016 import gateway_msgs.msg as gateway_msgs
00017 import rocon_gateway_utils
00018 import rosgraph
00019 from rosgraph.impl.graph import Edge, EdgeList
00020 import rocon_python_comms
00021 
00022 ##############################################################################
00023 # Graph
00024 ##############################################################################
00025 
00026 
00027 class Graph(object):
00028 
00029     '''
00030     Utility class for polling statistics from a running gateway-hub network.
00031     '''
00032 
00033     def __init__(self):
00034         '''
00035         Creates the polling topics necessary for updating statistics
00036         about the running gateway-hub network.
00037         '''
00038         self._last_update = 0
00039         self._gateway_namespace = None
00040         self._local_gateway = None
00041         self._remote_gateways = None
00042         self.gateway_nodes = []  # Gateway nodes
00043         self.flipped_nodes = []  # Flip connection nodes (i.e. topic name)
00044         self.pulled_nodes = []
00045         self.pulled_edges = []  # Gateway-Topic edges
00046         self.gateway_edges = []  # Gateway-Gateway edges
00047         self.flipped_edges = []  # All unconnected node-topics or topic-nodes
00048 
00049         # Rubbish to clear out once rocon_gateway_graph is integrated
00050         self.bad_nodes = []
00051 
00052         try:
00053             self._gateway_namespace = rocon_gateway_utils.resolve_local_gateway(timeout=rospy.rostime.Duration(2.0))
00054             self._gateway_info = rocon_python_comms.SubscriberProxy(
00055                 self._gateway_namespace + '/gateway_info', gateway_msgs.GatewayInfo)
00056             self._remote_gateway_info = rospy.ServiceProxy(
00057                 self._gateway_namespace + '/remote_gateway_info', gateway_srvs.RemoteGatewayInfo)
00058         except rocon_python_comms.NotFoundException as e:
00059             rospy.logerr("Gateway Graph: %s" % str(e))
00060             self._gateway_namespace = None
00061 
00062     def local_gateway_name(self):
00063         if self._local_gateway:
00064             return self._local_gateway.name
00065         else:
00066             return ''
00067 
00068     def update(self):
00069         if not self._gateway_namespace:
00070             return
00071         self._local_gateway = self._gateway_info()
00072         req = gateway_srvs.RemoteGatewayInfoRequest()
00073         req.gateways = []
00074         self._remote_gateways = self._remote_gateway_info(req).gateways
00075         self._last_update = rospy.get_rostime()
00076         # Gateways
00077         self.gateway_nodes.append(self._local_gateway.name)
00078         self.gateway_nodes.extend([remote_gateway.name for remote_gateway in self._remote_gateways])
00079         # Edges
00080         self.pulled_edges = EdgeList()
00081         self.gateway_edges = EdgeList()
00082         self.pulled_edges = EdgeList()
00083         self.flipped_edges = EdgeList()
00084         # Check local gateway
00085         for remote_rule in self._local_gateway.flipped_connections:
00086             self.gateway_edges.add(Edge(self._local_gateway.name, remote_rule.remote_rule.gateway))
00087             # this adds a bloody magic space, to help disambiguate node names from topic names
00088             connection_id = rosgraph.impl.graph.topic_node(
00089                 remote_rule.remote_rule.rule.name + '-' + remote_rule.remote_rule.rule.type)
00090             self.flipped_nodes.append(connection_id)
00091             self.flipped_edges.add(Edge(self._local_gateway.name, connection_id))
00092             self.flipped_edges.add(Edge(connection_id, remote_rule.remote_rule.gateway))
00093         for remote_rule in self._local_gateway.pulled_connections:
00094             connection_id = rosgraph.impl.graph.topic_node(remote_rule.rule.name + '-' + remote_rule.rule.type)
00095             self.pulled_nodes.append(connection_id)
00096             self.pulled_edges.add(Edge(self._local_gateway.name, connection_id))
00097             self.pulled_edges.add(Edge(connection_id, remote_rule.gateway))
00098         for rule in self._local_gateway.public_interface:
00099             connection_id = rosgraph.impl.graph.topic_node(rule.name + '-' + rule.type)
00100             # print "pulled edge: %s->%s" % (self._local_gateway.name, connection_id)
00101             self.pulled_nodes.append(connection_id)
00102             self.pulled_edges.add(Edge(self._local_gateway.name, connection_id))
00103         # Check remote gateways
00104         for remote_gateway in self._remote_gateways:
00105             for remote_rule in remote_gateway.flipped_interface:
00106                 connection_id = rosgraph.impl.graph.topic_node(remote_rule.rule.name + '-' + remote_rule.rule.type)
00107                 self.flipped_nodes.append(connection_id)
00108                 self.flipped_edges.add(Edge(remote_gateway.name, connection_id))
00109                 self.flipped_edges.add(Edge(connection_id, remote_rule.gateway))
00110                 self.gateway_edges.add(Edge(remote_gateway.name, remote_rule.gateway))
00111             for remote_rule in remote_gateway.pulled_interface:
00112                 connection_id = rosgraph.impl.graph.topic_node(remote_rule.rule.name + '-' + remote_rule.rule.type)
00113                 self.pulled_nodes.append(connection_id)
00114                 self.pulled_edges.add(Edge(remote_rule.gateway, connection_id))
00115                 self.pulled_edges.add(Edge(connection_id, remote_gateway.name))
00116                 self.gateway_edges.add(Edge(remote_gateway.name, remote_rule.gateway))


rocon_gateway
Author(s): Daniel Stonier , Jihoon Lee , Piyush Khandelwal
autogenerated on Sat Jun 8 2019 18:48:44