master_api.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 # Imports
00008 ##############################################################################
00009 
00010 import os
00011 import socket
00012 import httplib
00013 import errno
00014 import xmlrpclib
00015 from rosmaster.util import xmlrpcapi
00016 try:
00017     import urllib.parse as urlparse  # Python 3.x
00018 except ImportError:
00019     import urlparse
00020 import re
00021 
00022 import rospy
00023 import rosgraph
00024 import rostopic
00025 import rosservice
00026 import roslib.names
00027 from gateway_msgs.msg import Rule, ConnectionType
00028 
00029 from . import utils
00030 
00031 ##############################################################################
00032 # Aliases
00033 ##############################################################################
00034 
00035 # Can't see an easier way to alias or import these
00036 PUBLISHER = ConnectionType.PUBLISHER
00037 SUBSCRIBER = ConnectionType.SUBSCRIBER
00038 SERVICE = ConnectionType.SERVICE
00039 ACTION_SERVER = ConnectionType.ACTION_SERVER
00040 ACTION_CLIENT = ConnectionType.ACTION_CLIENT
00041 
00042 ##############################################################################
00043 # Master
00044 ##############################################################################
00045 
00046 
00047 class ConnectionCache(object):
00048 
00049     def __init__(self, get_system_state):
00050         self._get_system_state = get_system_state  # function call to the local master
00051         self._connections = {}
00052 #        self._system_state = {}
00053 #        self._system_state[PUBLISHER] = []
00054 #        self._system_state[SUBSCRIBER] = []
00055 #        self._system_state[SERVICE] = []
00056         self._connections = utils.create_empty_connection_type_dictionary()
00057 
00058     def update(self, new_system_state=None):
00059         '''
00060           Currently completely regenerating the connections dictionary and then taking
00061           diffs. Could be faster if we took diffs on the system state instead, but that's
00062           a bit more awkward since each element has a variable list of nodes that we'd have
00063           to check against to get good diffs. e.g.
00064             old_publishers = ['/chatter', ['/talker']]
00065             new_publishers = ['/chatter', ['/talker', '/babbler']]
00066         '''
00067         # init the variables we will return
00068         new_connections = utils.create_empty_connection_type_dictionary()
00069         lost_connections = utils.create_empty_connection_type_dictionary()
00070 
00071         if new_system_state is None:
00072             try:
00073                 publishers, subscribers, services = self._get_system_state()
00074             except socket.error:
00075                 rospy.logerr("Gateway : couldn't get system state from the master "
00076                              "[did you set your master uri to a wireless IP that just went down?]")
00077                 return new_connections, lost_connections
00078         else:
00079             publishers = new_system_state[PUBLISHER]
00080             subscribers = new_system_state[SUBSCRIBER]
00081             services = new_system_state[SERVICE]
00082         action_servers, publishers, subscribers = self._get_action_servers(publishers, subscribers)
00083         action_clients, publishers, subscribers = self._get_action_clients(publishers, subscribers)
00084         connections = utils.create_empty_connection_type_dictionary()
00085         connections[PUBLISHER] = self._get_connections_from_pub_sub_list(publishers, PUBLISHER)
00086         connections[SUBSCRIBER] = self._get_connections_from_pub_sub_list(subscribers, SUBSCRIBER)
00087         connections[SERVICE] = self._get_connections_from_service_list(services, SERVICE)
00088         connections[ACTION_SERVER] = self._get_connections_from_action_list(action_servers, ACTION_SERVER)
00089         connections[ACTION_CLIENT] = self._get_connections_from_action_list(action_clients, ACTION_CLIENT)
00090 
00091         # Will probably need to check not just in, but only name, node equal
00092         for connection_type in utils.connection_types:
00093             new_connections[connection_type] = utils.difflist(connections[connection_type], self._connections[connection_type])
00094             lost_connections[connection_type] = utils.difflist(self._connections[connection_type], connections[connection_type])
00095         self._connections = connections
00096         return new_connections, lost_connections
00097 
00098     def _is_topic_node_in_list(self, topic, node, topic_node_list):
00099         # check if cancel available
00100         available = False
00101         for candidate in topic_node_list:
00102             if candidate[0] == topic and node in candidate[1]:
00103                 available = True
00104                 break
00105         return available
00106 
00107     def _get_connections_from_action_list(self, connection_list, connection_type):
00108         connections = []
00109         for action in connection_list:
00110             action_name = action[0]
00111             #goal_topic = action_name + '/goal'
00112             #goal_topic_type = rostopic.get_topic_type(goal_topic)
00113             # topic_type = re.sub('ActionGoal$', '', goal_topic_type[0])  # Base type for action
00114             nodes = action[1]
00115             for node in nodes:
00116                 # try:
00117                 #    node_uri = self.lookupNode(node)
00118                 # except:
00119                 #    continue
00120                 rule = Rule(connection_type, action_name, node)
00121                 connection = utils.Connection(rule, None, None)  # topic_type, node_uri
00122                 connections.append(connection)
00123         return connections
00124 
00125     def _get_connections_from_service_list(self, connection_list, connection_type):
00126         connections = []
00127         for service in connection_list:
00128             service_name = service[0]
00129             #service_uri = rosservice.get_service_uri(service_name)
00130             nodes = service[1]
00131             for node in nodes:
00132                 # try:
00133                 #    node_uri = self.lookupNode(node)
00134                 # except:
00135                 #    continue
00136                 rule = Rule(connection_type, service_name, node)
00137                 connection = utils.Connection(rule, None, None)  # service_uri, node_uri
00138                 connections.append(connection)
00139         return connections
00140 
00141     def _get_connections_from_pub_sub_list(self, connection_list, connection_type):
00142         connections = []
00143         for topic in connection_list:
00144             topic_name = topic[0]
00145             #topic_type = rostopic.get_topic_type(topic_name)
00146             #topic_type = topic_type[0]
00147             nodes = topic[1]
00148             for node in nodes:
00149                 # try:
00150                     #node_uri = self.lookupNode(node)
00151                 # except:
00152                 #    continue
00153                 rule = Rule(connection_type, topic_name, node)
00154                 connection = utils.Connection(rule, None, None)  # topic_type, node_uri
00155                 connections.append(connection)
00156         return connections
00157 
00158     def _get_actions(self, pubs, subs):
00159         '''
00160           Return actions and pruned publisher, subscriber lists.
00161 
00162           @param publishers
00163           @type list of publishers in the form returned by rosgraph.Master.get_system_state
00164           @param subscribers
00165           @type list of subscribers in the form returned by rosgraph.Master.get_system_state
00166           @return list of actions, pruned_publishers, pruned_subscribers
00167           @rtype [base_topic, [nodes]], as param type, as param type
00168         '''
00169 
00170         actions = []
00171         for goal_candidate in pubs:
00172             if re.search('\/goal$', goal_candidate[0]):
00173                 # goal found, extract base topic
00174                 base_topic = re.sub('\/goal$', '', goal_candidate[0])
00175                 nodes = goal_candidate[1]
00176                 action_nodes = []
00177 
00178                 # there may be multiple nodes -- for each node search for the other topics
00179                 for node in nodes:
00180                     is_action = True
00181                     is_action &= self._is_topic_node_in_list(base_topic + '/goal', node, pubs)
00182                     is_action &= self._is_topic_node_in_list(base_topic + '/cancel', node, pubs)
00183                     is_action &= self._is_topic_node_in_list(base_topic + '/status', node, subs)
00184                     is_action &= self._is_topic_node_in_list(base_topic + '/feedback', node, subs)
00185                     is_action &= self._is_topic_node_in_list(base_topic + '/result', node, subs)
00186 
00187                     if is_action:
00188                         action_nodes.append(node)
00189 
00190                 if len(action_nodes) != 0:
00191                     # yay! an action has been found
00192                     actions.append([base_topic, action_nodes])
00193                     # remove action entries from publishers/subscribers
00194                     for connection in pubs:
00195                         if connection[0] in [base_topic + '/goal', base_topic + '/cancel']:
00196                             for node in action_nodes:
00197                                 try:
00198                                     connection[1].remove(node)
00199                                 except ValueError:
00200                                     rospy.logerr(
00201                                         "Gateway : couldn't remove an action publisher " +
00202                                         "from the master connections list [%s][%s]" %
00203                                         (connection[0], node))
00204                     for connection in subs:
00205                         if connection[0] in [base_topic + '/status', base_topic + '/feedback', base_topic + '/result']:
00206                             for node in action_nodes:
00207                                 try:
00208                                     connection[1].remove(node)
00209                                 except ValueError:
00210                                     rospy.logerr(
00211                                         "Gateway : couldn't remove an action subscriber " +
00212                                         "from the master connections list [%s][%s]" %
00213                                         (connection[0], node))
00214         pubs[:] = [connection for connection in pubs if len(connection[1]) != 0]
00215         subs[:] = [connection for connection in subs if len(connection[1]) != 0]
00216         return actions, pubs, subs
00217 
00218     def _get_action_servers(self, publishers, subscribers):
00219         '''
00220           Return action servers and pruned publisher, subscriber lists.
00221 
00222           @param publishers
00223           @type list of publishers in the form returned by rosgraph.Master.get_system_state
00224           @param subscribers
00225           @type list of subscribers in the form returned by rosgraph.Master.get_system_state
00226           @return list of actions, pruned_publishers, pruned_subscribers
00227           @rtype [base_topic, [nodes]], as param type, as param type
00228         '''
00229         actions, subs, pubs = self._get_actions(subscribers, publishers)
00230         return actions, pubs, subs
00231 
00232     def _get_action_clients(self, publishers, subscribers):
00233         '''
00234           Return action clients and pruned publisher, subscriber lists.
00235 
00236           @param publishers
00237           @type list of publishers in the form returned by rosgraph.Master.get_system_state
00238           @param subscribers
00239           @type list of subscribers in the form returned by rosgraph.Master.get_system_state
00240           @return list of actions, pruned_publishers, pruned_subscribers
00241           @rtype [base_topic, [nodes]], as param type, as param type
00242         '''
00243         actions, pubs, subs = self._get_actions(publishers, subscribers)
00244         return actions, pubs, subs
00245 
00246 
00247         # generate diffs
00248 #        new = {}
00249 #        lost = {}
00250 #        new[PUBLISHER] = utils.difflist(publishers, self._system_state[PUBLISHER])
00251 #        lost[PUBLISHER] = utils.difflist(self._system_state[PUBLISHER], publishers)
00252 #        self._is_topic_node_in_list(base_topic + '/goal', node, pubs)
00253 #        new[SUBSCRIBER] = utils.difflist(subscribers, self._system_state[SUBSCRIBER])
00254 #        lost[SUBSCRIBER] = utils.difflist(self._system_state[SUBSCRIBER], subscribers)
00255 #        new[SERVICE] = utils.difflist(services, self._system_state[SERVICE])
00256 #        lost[SERVICE] = utils.difflist(self._system_state[SERVICE], services)
00257 # cache new system state
00258 #        self._system_state[PUBLISHER] = copy.deepcopy(publishers)
00259 #        self._system_state[SUBSCRIBER] = copy.deepcopy(subscribers)
00260 #        self._system_state[SERVICE] = copy.deepcopy(services)
00261 #
00262 #        print("%s" % new[PUBLISHER])
00263 #        print("%s" % lost[PUBLISHER])
00264         # generate more diffs
00265 #        new[ACTION_SERVER], new[PUBLISHER], new[SUBSCRIBER] = self.get_action_servers(new[PUBLISHER], new[SUBSCRIBER])
00266 #        new[ACTION_CLIENT], new[PUBLISHER], new[SUBSCRIBER] = self.get_action_clients(new[PUBLISHER], new[SUBSCRIBER])
00267 #        lost[ACTION_SERVER], lost[PUBLISHER], lost[SUBSCRIBER] = \
00268 #            self.get_action_servers(lost[PUBLISHER], lost[SUBSCRIBER])
00269 #        lost[ACTION_CLIENT], lost[PUBLISHER], lost[SUBSCRIBER] = \
00270 #            self.get_action_clients(lost[PUBLISHER], lost[SUBSCRIBER])
00271 #
00272 #        self._connections[PUBLISHER].append(self.get_connections_from_pub_sub(new[PUBLISHER], PUBLISHER))
00273 #        self._connections[SUBSCRIBER].append(self.get_connections_from_pub_sub(new[SUBSCRIBER], SUBSCRIBER))
00274 #        self._connections[PUBLISHER] = list(set(self._connections[connection_type]) - set(lost[connection_type]))
00275 #
00276 #            topic_name = topic[0]
00277 #            topic_type = rostopic.get_topic_type(topic_name)
00278 #            topic_type = topic_type[0]
00279 #            nodes = topic[1]
00280 #            for node in nodes:
00281 #                try:
00282 #                    node_uri = self.lookupNode(node)
00283 #                except:
00284 #                    continue
00285 #                rule = Rule(connection_type, topic_name, node)
00286 #                connection = utils.Connection(rule, topic_type, node_uri)
00287 
00288 #    def _update_pub_sub_connections(self, connection_type, new_states, lost_states):
00289 #        for topic in new_states:
00290 #            topic_name = topic[0]
00291 #            nodes = topic[1]
00292 #            for node in nodes:
00293 #                rule = Rule(connection_type, topic_name, node)
00294 # connection = utils.Connection(rule, None, None)  # topic_type, node_uri)
00295 #                self._connections[connection_type].append(connection)
00296 #        lost_connections = []
00297 #        for topic in lost_states:
00298 #            topic_name = topic[0]
00299 #            nodes = topic[1]
00300 #            for node in nodes:
00301 #                rule = Rule(connection_type, topic_name, node)
00302 # connection = utils.Connection(rule, None, None)  # topic_type, node_uri)
00303 #                lost_connections.append(connection)
00304 # self._connections[connection_type][:] = [connection for connection in self._connections if ]
00305 
00306 
00307 class LocalMaster(rosgraph.Master):
00308 
00309     '''
00310       Representing a ros master (local ros master). Just contains a
00311       few utility methods for retrieving master related information as well
00312       as handles for registering and unregistering rules that have
00313       been pulled or flipped in from another gateway.
00314     '''
00315 
00316     def __init__(self):
00317         rosgraph.Master.__init__(self, rospy.get_name())
00318         # alias
00319         self.get_system_state = self.getSystemState
00320         self._connection_cache = ConnectionCache(self.get_system_state)
00321 
00322     ##########################################################################
00323     # Registration
00324     ##########################################################################
00325 
00326     def register(self, registration):
00327         '''
00328           Registers a rule with the local master.
00329 
00330           @param registration : registration details
00331           @type utils.Registration
00332 
00333           @return the updated registration object (only adds an anonymously generated local node name)
00334           @rtype utils.Registration
00335         '''
00336         # rograph.Master doesn't care whether the node is prefixed with slash or not, but we use it to
00337         # compare registrations later in FlippedInterface._is_registration_in_remote_rule()
00338         registration.local_node = "/" + self._get_anonymous_node_name(registration.connection.rule.node)
00339         rospy.logdebug("Gateway : registering a new node [%s] for [%s]" % (registration.local_node, registration))
00340 
00341         # Then do we need checkIfIsLocal? Needs lots of parsing time, and the outer class should
00342         # already have handle that.
00343 
00344         node_master = rosgraph.Master(registration.local_node)
00345         if registration.connection.rule.type == PUBLISHER:
00346             node_master.registerPublisher(
00347                 registration.connection.rule.name,
00348                 registration.connection.type_info,
00349                 registration.connection.xmlrpc_uri)
00350             return registration
00351         elif registration.connection.rule.type == SUBSCRIBER:
00352             self._register_subscriber(
00353                 node_master,
00354                 registration.connection.rule.name,
00355                 registration.connection.type_info,
00356                 registration.connection.xmlrpc_uri)
00357             return registration
00358         elif registration.connection.rule.type == SERVICE:
00359             node_name = rosservice.get_service_node(registration.connection.rule.name)
00360             if node_name is not None:
00361                 rospy.logwarn(
00362                     "Gateway : tried to register a service that is already locally available, aborting [%s][%s]" %
00363                     (registration.connection.rule.name, node_name))
00364                 return None
00365             else:
00366                 if registration.connection.rule.name is None:
00367                     rospy.logerr(
00368                         "Gateway : tried to register a service with name set to None [%s, %s, %s]" %
00369                         (registration.connection.rule.name,
00370                          registration.connection.type_info,
00371                          registration.connection.xmlrpc_uri))
00372                     return None
00373                 if registration.connection.type_info is None:
00374                     rospy.logerr(
00375                         "Gateway : tried to register a service with type_info set to None [%s, %s, %s]" %
00376                         (registration.connection.rule.name,
00377                          registration.connection.type_info,
00378                          registration.connection.xmlrpc_uri))
00379                     return None
00380                 if registration.connection.xmlrpc_uri is None:
00381                     rospy.logerr(
00382                         "Gateway : tried to register a service with xmlrpc_uri set to None [%s, %s, %s]" %
00383                         (registration.connection.rule.name,
00384                          registration.connection.type_info,
00385                          registration.connection.xmlrpc_uri))
00386                     return None
00387                 try:
00388                     node_master.registerService(
00389                         registration.connection.rule.name,
00390                         registration.connection.type_info,
00391                         registration.connection.xmlrpc_uri)
00392                 except rosgraph.masterapi.Error as e:
00393                     rospy.logerr("Gateway : got error trying to register a service on the local master [%s][%s]" % (
00394                         registration.connection.rule.name, str(e)))
00395                     return None
00396                 except rosgraph.masterapi.Failure as e:
00397                     rospy.logerr("Gateway : failed to register a service on the local master [%s][%s]" % (
00398                         registration.connection.rule.name, str(e)))
00399                     return None
00400                 return registration
00401         elif registration.connection.rule.type == ACTION_SERVER:
00402             # Need to update these with self._register_subscriber
00403             self._register_subscriber(
00404                 node_master,
00405                 registration.connection.rule.name +
00406                 "/goal",
00407                 registration.connection.type_info +
00408                 "ActionGoal",
00409                 registration.connection.xmlrpc_uri)
00410             self._register_subscriber(
00411                 node_master,
00412                 registration.connection.rule.name +
00413                 "/cancel",
00414                 "actionlib_msgs/GoalID",
00415                 registration.connection.xmlrpc_uri)
00416             node_master.registerPublisher(
00417                 registration.connection.rule.name +
00418                 "/status",
00419                 "actionlib_msgs/GoalStatusArray",
00420                 registration.connection.xmlrpc_uri)
00421             node_master.registerPublisher(
00422                 registration.connection.rule.name +
00423                 "/feedback",
00424                 registration.connection.type_info +
00425                 "ActionFeedback",
00426                 registration.connection.xmlrpc_uri)
00427             node_master.registerPublisher(
00428                 registration.connection.rule.name +
00429                 "/result",
00430                 registration.connection.type_info +
00431                 "ActionResult",
00432                 registration.connection.xmlrpc_uri)
00433             return registration
00434         elif registration.connection.rule.type == ACTION_CLIENT:
00435             node_master.registerPublisher(
00436                 registration.connection.rule.name +
00437                 "/goal",
00438                 registration.connection.type_info +
00439                 "ActionGoal",
00440                 registration.connection.xmlrpc_uri)
00441             node_master.registerPublisher(
00442                 registration.connection.rule.name +
00443                 "/cancel",
00444                 "actionlib_msgs/GoalID",
00445                 registration.connection.xmlrpc_uri)
00446             self._register_subscriber(node_master, registration.connection.rule.name +
00447                                       "/status", "actionlib_msgs/GoalStatusArray", registration.connection.xmlrpc_uri)
00448             self._register_subscriber(
00449                 node_master,
00450                 registration.connection.rule.name +
00451                 "/feedback",
00452                 registration.connection.type_info +
00453                 "ActionFeedback",
00454                 registration.connection.xmlrpc_uri)
00455             self._register_subscriber(
00456                 node_master,
00457                 registration.connection.rule.name +
00458                 "/result",
00459                 registration.connection.type_info +
00460                 "ActionResult",
00461                 registration.connection.xmlrpc_uri)
00462             return registration
00463         return None
00464 
00465     def unregister(self, registration):
00466         '''
00467           Unregisters a rule with the local master.
00468 
00469           @param registration : registration details for an existing gateway registered rule
00470           @type utils.Registration
00471         '''
00472         node_master = rosgraph.Master(registration.local_node)
00473         rospy.logdebug("Gateway : unregistering local node [%s] for [%s]" % (registration.local_node, registration))
00474         if registration.connection.rule.type == PUBLISHER:
00475             node_master.unregisterPublisher(registration.connection.rule.name, registration.connection.xmlrpc_uri)
00476         elif registration.connection.rule.type == SUBSCRIBER:
00477             self._unregister_subscriber(
00478                 node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name)
00479         elif registration.connection.rule.type == SERVICE:
00480             node_master.unregisterService(registration.connection.rule.name, registration.connection.type_info)
00481         elif registration.connection.rule.type == ACTION_SERVER:
00482             self._unregister_subscriber(
00483                 node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/goal")
00484             self._unregister_subscriber(
00485                 node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/cancel")
00486             node_master.unregisterPublisher(
00487                 registration.connection.rule.name + "/status", registration.connection.xmlrpc_uri)
00488             node_master.unregisterPublisher(
00489                 registration.connection.rule.name + "/feedback", registration.connection.xmlrpc_uri)
00490             node_master.unregisterPublisher(
00491                 registration.connection.rule.name + "/result", registration.connection.xmlrpc_uri)
00492         elif registration.connection.rule.type == ACTION_CLIENT:
00493             node_master.unregisterPublisher(
00494                 registration.connection.rule.name + "/goal", registration.connection.xmlrpc_uri)
00495             node_master.unregisterPublisher(
00496                 registration.connection.rule.name + "/cancel", registration.connection.xmlrpc_uri)
00497             self._unregister_subscriber(
00498                 node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/status")
00499             self._unregister_subscriber(
00500                 node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/feedback")
00501             self._unregister_subscriber(
00502                 node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/result")
00503 
00504     def _register_subscriber(self, node_master, name, type_info, xmlrpc_uri):
00505         '''
00506           This one is not necessary, since you can pretty much guarantee the
00507           existence of the subscriber here, but it pays to be safe - we've seen
00508           some errors come out here when the ROS_MASTER_URI was only set to
00509           localhost.
00510 
00511           @param node_master : node-master xmlrpc method handler
00512           @param type_info : type of the subscriber message
00513           @param xmlrpc_uri : the uri of the node (xmlrpc server)
00514           @type string
00515           @param name : fully resolved subscriber name
00516         '''
00517         # This unfortunately is a game breaker - it destroys all connections, not just those
00518         # connected to this master, see #125.
00519         pub_uri_list = node_master.registerSubscriber(name, type_info, xmlrpc_uri)
00520         try:
00521             #rospy.loginfo("register_subscriber [%s][%s][%s]" % (name, xmlrpc_uri, pub_uri_list))
00522             xmlrpcapi(xmlrpc_uri).publisherUpdate('/master', name, pub_uri_list)
00523         except socket.error as v:
00524             errorcode = v[0]
00525             if errorcode != errno.ECONNREFUSED:
00526                 rospy.logerr(
00527                     "Gateway : error registering subscriber " +
00528                     "(is ROS_MASTER_URI and ROS_HOSTNAME or ROS_IP correctly set?)")
00529                 rospy.logerr("Gateway : errorcode [%s] xmlrpc_uri [%s]" % (str(errorcode), xmlrpc_uri))
00530                 raise  # better handling here would be ideal
00531             else:
00532                 pass  # subscriber stopped on the other side, don't worry about it
00533 
00534     def _unregister_subscriber(self, node_master, xmlrpc_uri, name):
00535         '''
00536           It is a special case as it requires xmlrpc handling to inform the subscriber of
00537           the disappearance of publishers it was connected to. It also needs to handle the
00538           case when that information doesn't get to the subscriber because it is down.
00539 
00540           @param node_master : node-master xmlrpc method handler
00541           @param xmlrpc_uri : the uri of the node (xmlrpc server)
00542           @type string
00543           @param name : fully resolved subscriber name
00544         '''
00545         # This unfortunately is a game breaker - it destroys all connections, not just those
00546         # connected to this master, see #125.
00547         try:
00548             xmlrpcapi(xmlrpc_uri).publisherUpdate('/master', name, [])
00549         except socket.error as v:
00550             errorcode = v[0]
00551             if errorcode != errno.ECONNREFUSED:
00552                 raise  # better handling here would be ideal
00553             else:
00554                 pass  # subscriber stopped on the other side, don't worry about it
00555         except xmlrpclib.Fault:
00556             # This occurs when the subscriber has gone down and unflipped.
00557             # For us this is not an error since we were only informing
00558             # the subscriber of an updated publisher state...which
00559             # it no longer needs!
00560             pass
00561         except httplib.CannotSendRequest:
00562             # This occurs if the master has shut down, just ignore this gracefully.
00563             # I'm not aware that it's important to catch this at any othe time.
00564             pass
00565         node_master.unregisterSubscriber(name, xmlrpc_uri)
00566 
00567     ##########################################################################
00568     # Master utility methods
00569     ##########################################################################
00570 
00571     def generate_connection_details(self, connection_type, name, node):
00572         '''
00573         Creates all the extra details to create a connection object from a
00574         rule.
00575 
00576         @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType)
00577         @type string
00578         @param name : the name of the connection
00579         @type string
00580         @param node : the master node name it comes from
00581         @param string
00582 
00583         @return the utils.Connection object complete with type_info and xmlrpc_uri
00584         @type utils.Connection
00585         '''
00586         # Very important here to check for the results of xmlrpc_uri and especially topic_type
00587         #     https://github.com/robotics-in-concert/rocon_multimaster/issues/173
00588         # In the watcher thread, we get the local connection index (whereby the arguments of this function
00589         # come from) via master.get_connection_state. That means there is a small amount of time from
00590         # getting the topic name, to checking for hte xmlrpc_uri and especially topic_type here in which
00591         # the topic could have disappeared. When this happens, it returns None.
00592         connections = []
00593         xmlrpc_uri = node.split(",")[1]
00594         node = node.split(",")[0]
00595 
00596         if xmlrpc_uri is None:
00597             return connections
00598         if connection_type == PUBLISHER or connection_type == SUBSCRIBER:
00599             type_info = rostopic.get_topic_type(name)[0]  # message type
00600             if type_info is not None:
00601                 connections.append(utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri))
00602             else:
00603                 rospy.logwarn('Gateway : [%s] does not have type_info. Cannot flip' % name)
00604         elif connection_type == SERVICE:
00605             type_info = rosservice.get_service_uri(name)
00606             if type_info is not None:
00607                 connections.append(utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri))
00608         elif connection_type == ACTION_SERVER:
00609             goal_type_info = rostopic.get_topic_type(name + '/goal')[0]  # message type
00610             cancel_type_info = rostopic.get_topic_type(name + '/cancel')[0]  # message type
00611             status_type_info = rostopic.get_topic_type(name + '/status')[0]  # message type
00612             feedback_type_info = rostopic.get_topic_type(name + '/feedback')[0]  # message type
00613             result_type_info = rostopic.get_topic_type(name + '/result')[0]  # message type
00614             if (
00615                 goal_type_info is not None and cancel_type_info is not None and
00616                 status_type_info is not None and feedback_type_info is not None and
00617                 result_type_info is not None
00618             ):
00619                 connections.append(utils.Connection(Rule(SUBSCRIBER, name + '/goal', node), goal_type_info, xmlrpc_uri))
00620                 connections.append(
00621                     utils.Connection(Rule(SUBSCRIBER, name + '/cancel', node), cancel_type_info, xmlrpc_uri))
00622                 connections.append(
00623                     utils.Connection(Rule(PUBLISHER, name + '/status', node), status_type_info, xmlrpc_uri))
00624                 connections.append(
00625                     utils.Connection(Rule(PUBLISHER, name + '/feedback', node), feedback_type_info, xmlrpc_uri))
00626                 connections.append(
00627                     utils.Connection(Rule(PUBLISHER, name + '/result', node), result_type_info, xmlrpc_uri))
00628         elif connection_type == ACTION_CLIENT:
00629             goal_type_info = rostopic.get_topic_type(name + '/goal')[0]  # message type
00630             cancel_type_info = rostopic.get_topic_type(name + '/cancel')[0]  # message type
00631             status_type_info = rostopic.get_topic_type(name + '/status')[0]  # message type
00632             feedback_type_info = rostopic.get_topic_type(name + '/feedback')[0]  # message type
00633             result_type_info = rostopic.get_topic_type(name + '/result')[0]  # message type
00634             if (
00635                 goal_type_info is not None and cancel_type_info is not None and
00636                 status_type_info is not None and feedback_type_info is not None and
00637                 result_type_info is not None
00638             ):
00639                 connections.append(utils.Connection(Rule(PUBLISHER, name + '/goal', node), goal_type_info, xmlrpc_uri))
00640                 connections.append(
00641                     utils.Connection(Rule(PUBLISHER, name + '/cancel', node), cancel_type_info, xmlrpc_uri))
00642                 connections.append(
00643                     utils.Connection(Rule(SUBSCRIBER, name + '/status', node), status_type_info, xmlrpc_uri))
00644                 connections.append(
00645                     utils.Connection(Rule(SUBSCRIBER, name + '/feedback', node), feedback_type_info, xmlrpc_uri))
00646                 connections.append(
00647                     utils.Connection(Rule(SUBSCRIBER, name + '/result', node), result_type_info, xmlrpc_uri))
00648         return connections
00649 
00650     def generate_advertisement_connection_details(self, connection_type, name, node):
00651         '''
00652         Creates all the extra details to create a connection object from an
00653         advertisement rule. This is a bit different to the previous one - we just need
00654         the type and single node uri that everything originates from (don't need to generate all
00655         the pub/sub connections themselves.
00656 
00657         Probably flips could be merged into this sometime, but it'd be a bit gnarly.
00658 
00659         @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType)
00660         @type string
00661         @param name : the name of the connection
00662         @type string
00663         @param node : the master node name it comes from
00664         @param string
00665 
00666         @return the utils.Connection object complete with type_info and xmlrpc_uri
00667         @type utils.Connection
00668         '''
00669         # Very important here to check for the results of xmlrpc_uri and especially topic_type
00670         #     https://github.com/robotics-in-concert/rocon_multimaster/issues/173
00671         # In the watcher thread, we get the local connection index (whereby the arguments of this function
00672         # come from) via master.get_connection_state. That means there is a small amount of time from
00673         # getting the topic name, to checking for hte xmlrpc_uri and especially topic_type here in which
00674         # the topic could have disappeared. When this happens, it returns None.
00675         connection = None
00676         xmlrpc_uri = self.lookupNode(node)
00677         if xmlrpc_uri is None:
00678             return connection
00679         if connection_type == PUBLISHER or connection_type == SUBSCRIBER:
00680             type_info = rostopic.get_topic_type(name)[0]  # message type
00681             if type_info is not None:
00682                 connection = utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri)
00683         elif connection_type == SERVICE:
00684             type_info = rosservice.get_service_uri(name)
00685             if type_info is not None:
00686                 connection = utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri)
00687         elif connection_type == ACTION_SERVER or connection_type == ACTION_CLIENT:
00688             goal_topic = name + '/goal'
00689             goal_topic_type = rostopic.get_topic_type(goal_topic)
00690             type_info = re.sub('ActionGoal$', '', goal_topic_type[0])  # Base type for action
00691             if type_info is not None:
00692                 connection = utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri)
00693         return connection
00694 
00695     def get_ros_ip(self):
00696         o = urlparse.urlparse(rosgraph.get_master_uri())
00697         if o.hostname == 'localhost':
00698             ros_ip = ''
00699             try:
00700                 ros_ip = os.environ['ROS_IP']
00701             except Exception:
00702                 try:
00703                     # often people use this one instead
00704                     ros_ip = os.environ['ROS_HOSTNAME']
00705                 except Exception:
00706                     # should probably check other means here - e.g. first of the system ipconfig
00707                     rospy.logwarn("Gateway : no valid ip found for this host, just setting 'localhost'")
00708                     return 'localhost'
00709             return ros_ip
00710         else:
00711             return o.hostname
00712 
00713     def get_connection_state(self):
00714         unused_new_connections, unused_lost_connections = self._connection_cache.update()
00715         # This would be more optimal, but we'll have to perturb lots of code
00716         # return new_connections, lost_connections
00717         return self._connection_cache._connections
00718 
00719     def _get_anonymous_node_name(self, topic):
00720         t = topic[1:len(topic)]
00721         name = roslib.names.anonymous_name(t)
00722         return name


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