Package rocon_gateway :: Module master_api
[frames] | no frames]

Source Code for Module rocon_gateway.master_api

  1  #!/usr/bin/env python 
  2  # 
  3  # License: BSD 
  4  #   https://raw.github.com/robotics-in-concert/rocon_multimaster/master/rocon_gateway/LICENSE 
  5  # 
  6   
  7  ############################################################################## 
  8  # Imports 
  9  ############################################################################## 
 10   
 11  import os 
 12  import socket 
 13  import errno 
 14  import rospy 
 15  import rosgraph 
 16  import rostopic 
 17  import rosservice 
 18  import roslib.names 
 19  from rosmaster.util import xmlrpcapi 
 20  try: 
 21      import urllib.parse as urlparse  # Python 3.x 
 22  except ImportError: 
 23      import urlparse 
 24  import re 
 25  from gateway_msgs.msg import Rule, ConnectionType 
 26   
 27  # local imports 
 28  import utils 
 29   
 30  # Can't see an easier way to alias or import these 
 31  PUBLISHER = ConnectionType.PUBLISHER 
 32  SUBSCRIBER = ConnectionType.SUBSCRIBER 
 33  SERVICE = ConnectionType.SERVICE 
 34  ACTION_SERVER = ConnectionType.ACTION_SERVER 
 35  ACTION_CLIENT = ConnectionType.ACTION_CLIENT 
 36   
 37  ############################################################################## 
 38  # Master 
 39  ############################################################################## 
 40   
 41   
42 -class ConnectionCache(object):
43
44 - def __init__(self, get_system_state):
45 self._get_system_state = get_system_state # function call to the local master 46 self._connections = {} 47 # self._system_state = {} 48 # self._system_state[PUBLISHER] = [] 49 # self._system_state[SUBSCRIBER] = [] 50 # self._system_state[SERVICE] = [] 51 self._connections = utils.create_empty_connection_type_dictionary()
52
53 - def update(self, new_system_state=None):
54 ''' 55 Currently completely regenerating the connections dictionary and then taking 56 diffs. Could be faster if we took diffs on the system state instead, but that's 57 a bit more awkward since each element has a variable list of nodes that we'd have 58 to check against to get good diffs. e.g. 59 old_publishers = ['/chatter', ['/talker']] 60 new_publishers = ['/chatter', ['/talker', '/babbler']] 61 ''' 62 if new_system_state is None: 63 publishers, subscribers, services = self._get_system_state() 64 else: 65 publishers = new_system_state[PUBLISHER] 66 subscribers = new_system_state[SUBSCRIBER] 67 services = new_system_state[SERVICE] 68 action_servers, publishers, subscribers = self._get_action_servers(publishers, subscribers) 69 action_clients, publishers, subscribers = self._get_action_clients(publishers, subscribers) 70 connections = utils.create_empty_connection_type_dictionary() 71 connections[PUBLISHER] = self._get_connections_from_pub_sub_list(publishers, PUBLISHER) 72 connections[SUBSCRIBER] = self._get_connections_from_pub_sub_list(subscribers, SUBSCRIBER) 73 connections[SERVICE] = self._get_connections_from_service_list(services, SERVICE) 74 connections[ACTION_SERVER] = self._get_connections_from_action_list(action_servers, ACTION_SERVER) 75 connections[ACTION_CLIENT] = self._get_connections_from_action_list(action_clients, ACTION_CLIENT) 76 77 # Will probably need to check not just in, but only name, node equal 78 diff = lambda l1, l2: [x for x in l1 if x not in l2] 79 new_connections = utils.create_empty_connection_type_dictionary() 80 lost_connections = utils.create_empty_connection_type_dictionary() 81 for connection_type in utils.connection_types: 82 new_connections[connection_type] = diff(connections[connection_type], self._connections[connection_type]) 83 lost_connections[connection_type] = diff(self._connections[connection_type], connections[connection_type]) 84 self._connections = connections 85 return new_connections, lost_connections
86
87 - def _is_topic_node_in_list(self, topic, node, topic_node_list):
88 # check if cancel available 89 available = False 90 for candidate in topic_node_list: 91 if candidate[0] == topic and node in candidate[1]: 92 available = True 93 break 94 return available
95
96 - def _get_connections_from_action_list(self, connection_list, connection_type):
97 connections = [] 98 for action in connection_list: 99 action_name = action[0] 100 #goal_topic = action_name + '/goal' 101 #goal_topic_type = rostopic.get_topic_type(goal_topic) 102 #topic_type = re.sub('ActionGoal$', '', goal_topic_type[0]) # Base type for action 103 nodes = action[1] 104 for node in nodes: 105 #try: 106 # node_uri = self.lookupNode(node) 107 #except: 108 # continue 109 rule = Rule(connection_type, action_name, node) 110 connection = utils.Connection(rule, None, None) # topic_type, node_uri 111 connections.append(connection) 112 return connections
113
114 - def _get_connections_from_service_list(self, connection_list, connection_type):
115 connections = [] 116 for service in connection_list: 117 service_name = service[0] 118 #service_uri = rosservice.get_service_uri(service_name) 119 nodes = service[1] 120 for node in nodes: 121 #try: 122 # node_uri = self.lookupNode(node) 123 #except: 124 # continue 125 rule = Rule(connection_type, service_name, node) 126 connection = utils.Connection(rule, None, None) # service_uri, node_uri 127 connections.append(connection) 128 return connections
129
130 - def _get_connections_from_pub_sub_list(self, connection_list, connection_type):
131 connections = [] 132 for topic in connection_list: 133 topic_name = topic[0] 134 #topic_type = rostopic.get_topic_type(topic_name) 135 #topic_type = topic_type[0] 136 nodes = topic[1] 137 for node in nodes: 138 #try: 139 #node_uri = self.lookupNode(node) 140 #except: 141 # continue 142 rule = Rule(connection_type, topic_name, node) 143 connection = utils.Connection(rule, None, None) # topic_type, node_uri 144 connections.append(connection) 145 return connections
146
147 - def _get_actions(self, pubs, subs):
148 ''' 149 Return actions and pruned publisher, subscriber lists. 150 151 @param publishers 152 @type list of publishers in the form returned by rosgraph.Master.get_system_state 153 @param subscribers 154 @type list of subscribers in the form returned by rosgraph.Master.get_system_state 155 @return list of actions, pruned_publishers, pruned_subscribers 156 @rtype [base_topic, [nodes]], as param type, as param type 157 ''' 158 159 actions = [] 160 for goal_candidate in pubs: 161 if re.search('\/goal$', goal_candidate[0]): 162 # goal found, extract base topic 163 base_topic = re.sub('\/goal$', '', goal_candidate[0]) 164 nodes = goal_candidate[1] 165 action_nodes = [] 166 167 # there may be multiple nodes -- for each node search for the other topics 168 for node in nodes: 169 is_action = True 170 is_action &= self._is_topic_node_in_list(base_topic + '/goal', node, pubs) 171 is_action &= self._is_topic_node_in_list(base_topic + '/cancel', node, pubs) 172 is_action &= self._is_topic_node_in_list(base_topic + '/status', node, subs) 173 is_action &= self._is_topic_node_in_list(base_topic + '/feedback', node, subs) 174 is_action &= self._is_topic_node_in_list(base_topic + '/result', node, subs) 175 176 if is_action: 177 action_nodes.append(node) 178 179 if len(action_nodes) != 0: 180 # yay! an action has been found 181 actions.append([base_topic, action_nodes]) 182 # remove action entries from publishers/subscribers 183 for connection in pubs: 184 if connection[0] in [base_topic + '/goal', base_topic + '/cancel']: 185 for node in action_nodes: 186 try: 187 connection[1].remove(node) 188 except ValueError: 189 rospy.logerr("Gateway : couldn't remove an action publisher from the master connections list [%s][%s]" % (connection[0], node)) 190 for connection in subs: 191 if connection[0] in [base_topic + '/status', base_topic + '/feedback', base_topic + '/result']: 192 for node in action_nodes: 193 try: 194 connection[1].remove(node) 195 except ValueError: 196 rospy.logerr("Gateway : couldn't remove an action subscriber from the master connections list [%s][%s]" % (connection[0], node)) 197 pubs[:] = [connection for connection in pubs if len(connection[1]) != 0] 198 subs[:] = [connection for connection in subs if len(connection[1]) != 0] 199 return actions, pubs, subs
200
201 - def _get_action_servers(self, publishers, subscribers):
202 ''' 203 Return action servers and pruned publisher, subscriber lists. 204 205 @param publishers 206 @type list of publishers in the form returned by rosgraph.Master.get_system_state 207 @param subscribers 208 @type list of subscribers in the form returned by rosgraph.Master.get_system_state 209 @return list of actions, pruned_publishers, pruned_subscribers 210 @rtype [base_topic, [nodes]], as param type, as param type 211 ''' 212 actions, subs, pubs = self._get_actions(subscribers, publishers) 213 return actions, pubs, subs
214
215 - def _get_action_clients(self, publishers, subscribers):
216 ''' 217 Return action clients and pruned publisher, subscriber lists. 218 219 @param publishers 220 @type list of publishers in the form returned by rosgraph.Master.get_system_state 221 @param subscribers 222 @type list of subscribers in the form returned by rosgraph.Master.get_system_state 223 @return list of actions, pruned_publishers, pruned_subscribers 224 @rtype [base_topic, [nodes]], as param type, as param type 225 ''' 226 actions, pubs, subs = self._get_actions(publishers, subscribers) 227 return actions, pubs, subs
228 229 230 # generate diffs 231 # diff = lambda l1, l2: [x for x in l1 if x not in l2] 232 # new = {} 233 # lost = {} 234 # new[PUBLISHER] = diff(publishers, self._system_state[PUBLISHER]) 235 # lost[PUBLISHER] = diff(self._system_state[PUBLISHER], publishers) 236 # self._is_topic_node_in_list(base_topic + '/goal', node, pubs) 237 # new[SUBSCRIBER] = diff(subscribers, self._system_state[SUBSCRIBER]) 238 # lost[SUBSCRIBER] = diff(self._system_state[SUBSCRIBER], subscribers) 239 # new[SERVICE] = diff(services, self._system_state[SERVICE]) 240 # lost[SERVICE] = diff(self._system_state[SERVICE], services) 241 # # cache new system state 242 # self._system_state[PUBLISHER] = copy.deepcopy(publishers) 243 # self._system_state[SUBSCRIBER] = copy.deepcopy(subscribers) 244 # self._system_state[SERVICE] = copy.deepcopy(services) 245 # 246 # print("%s" % new[PUBLISHER]) 247 # print("%s" % lost[PUBLISHER]) 248 # generate more diffs 249 # new[ACTION_SERVER], new[PUBLISHER], new[SUBSCRIBER] = self.get_action_servers(new[PUBLISHER], new[SUBSCRIBER]) 250 # new[ACTION_CLIENT], new[PUBLISHER], new[SUBSCRIBER] = self.get_action_clients(new[PUBLISHER], new[SUBSCRIBER]) 251 # lost[ACTION_SERVER], lost[PUBLISHER], lost[SUBSCRIBER] = self.get_action_servers(lost[PUBLISHER], lost[SUBSCRIBER]) 252 # lost[ACTION_CLIENT], lost[PUBLISHER], lost[SUBSCRIBER] = self.get_action_clients(lost[PUBLISHER], lost[SUBSCRIBER]) 253 # 254 # self._connections[PUBLISHER].append(self.get_connections_from_pub_sub(new[PUBLISHER], PUBLISHER)) 255 # self._connections[SUBSCRIBER].append(self.get_connections_from_pub_sub(new[SUBSCRIBER], SUBSCRIBER)) 256 # self._connections[PUBLISHER] = list(set(self._connections[connection_type]) - set(lost[connection_type])) 257 # 258 # topic_name = topic[0] 259 # topic_type = rostopic.get_topic_type(topic_name) 260 # topic_type = topic_type[0] 261 # nodes = topic[1] 262 # for node in nodes: 263 # try: 264 # node_uri = self.lookupNode(node) 265 # except: 266 # continue 267 # rule = Rule(connection_type, topic_name, node) 268 # connection = utils.Connection(rule, topic_type, node_uri) 269 270 # def _update_pub_sub_connections(self, connection_type, new_states, lost_states): 271 # for topic in new_states: 272 # topic_name = topic[0] 273 # nodes = topic[1] 274 # for node in nodes: 275 # rule = Rule(connection_type, topic_name, node) 276 # connection = utils.Connection(rule, None, None) # topic_type, node_uri) 277 # self._connections[connection_type].append(connection) 278 # lost_connections = [] 279 # for topic in lost_states: 280 # topic_name = topic[0] 281 # nodes = topic[1] 282 # for node in nodes: 283 # rule = Rule(connection_type, topic_name, node) 284 # connection = utils.Connection(rule, None, None) # topic_type, node_uri) 285 # lost_connections.append(connection) 286 ## self._connections[connection_type][:] = [connection for connection in self._connections if ] 287 288
289 -class LocalMaster(rosgraph.Master):
290 ''' 291 Representing a ros master (local ros master). Just contains a 292 few utility methods for retrieving master related information as well 293 as handles for registering and unregistering rules that have 294 been pulled or flipped in from another gateway. 295 ''' 296
297 - def __init__(self):
298 rosgraph.Master.__init__(self, rospy.get_name()) 299 # alias 300 self.get_system_state = self.getSystemState 301 self._connection_cache = ConnectionCache(self.get_system_state)
302 303 ########################################################################## 304 # Registration 305 ########################################################################## 306
307 - def register(self, registration):
308 ''' 309 Registers a rule with the local master. 310 311 @param registration : registration details 312 @type utils.Registration 313 314 @return the updated registration object (only adds an anonymously generated local node name) 315 @rtype utils.Registration 316 ''' 317 registration.local_node = self._get_anonymous_node_name(registration.connection.rule.node) 318 rospy.logdebug("Gateway : registering a new node [%s] for [%s]" % (registration.local_node, registration)) 319 320 # Then do we need checkIfIsLocal? Needs lots of parsing time, and the outer class should 321 # already have handle that. 322 323 node_master = rosgraph.Master(registration.local_node) 324 if registration.connection.rule.type == PUBLISHER: 325 node_master.registerPublisher(registration.connection.rule.name, registration.connection.type_info, registration.connection.xmlrpc_uri) 326 return registration 327 elif registration.connection.rule.type == SUBSCRIBER: 328 self._register_subscriber(node_master, registration.connection.rule.name, registration.connection.type_info, registration.connection.xmlrpc_uri) 329 return registration 330 elif registration.connection.rule.type == SERVICE: 331 if rosservice.get_service_node(registration.connection.rule.name): 332 rospy.logwarn("Gateway : tried to register a service that is already locally available, aborting [%s]" % registration.connection.rule.name) 333 return None 334 else: 335 node_master.registerService(registration.connection.rule.name, registration.connection.type_info, registration.connection.xmlrpc_uri) 336 return registration 337 elif registration.connection.rule.type == ACTION_SERVER: 338 # Need to update these with self._register_subscriber 339 self._register_subscriber(node_master, registration.connection.rule.name + "/goal", registration.connection.type_info + "ActionGoal", registration.connection.xmlrpc_uri) 340 self._register_subscriber(node_master, registration.connection.rule.name + "/cancel", "actionlib_msgs/GoalID", registration.connection.xmlrpc_uri) 341 node_master.registerPublisher(registration.connection.rule.name + "/status", "actionlib_msgs/GoalStatusArray", registration.connection.xmlrpc_uri) 342 node_master.registerPublisher(registration.connection.rule.name + "/feedback", registration.connection.type_info + "ActionFeedback", registration.connection.xmlrpc_uri) 343 node_master.registerPublisher(registration.connection.rule.name + "/result", registration.connection.type_info + "ActionResult", registration.connection.xmlrpc_uri) 344 return registration 345 elif registration.connection.rule.type == ACTION_CLIENT: 346 node_master.registerPublisher(registration.connection.rule.name + "/goal", registration.connection.type_info + "ActionGoal", registration.connection.xmlrpc_uri) 347 node_master.registerPublisher(registration.connection.rule.name + "/cancel", "actionlib_msgs/GoalID", registration.connection.xmlrpc_uri) 348 self._register_subscriber(node_master, registration.connection.rule.name + "/status", "actionlib_msgs/GoalStatusArray", registration.connection.xmlrpc_uri) 349 self._register_subscriber(node_master, registration.connection.rule.name + "/feedback", registration.connection.type_info + "ActionFeedback", registration.connection.xmlrpc_uri) 350 self._register_subscriber(node_master, registration.connection.rule.name + "/result", registration.connection.type_info + "ActionResult", registration.connection.xmlrpc_uri) 351 return registration 352 return None
353
354 - def unregister(self, registration):
355 ''' 356 Unregisters a rule with the local master. 357 358 @param registration : registration details for an existing gateway registered rule 359 @type utils.Registration 360 ''' 361 node_master = rosgraph.Master(registration.local_node) 362 rospy.logdebug("Gateway : unregistering local node [%s] for [%s]" % (registration.local_node, registration)) 363 if registration.connection.rule.type == PUBLISHER: 364 node_master.unregisterPublisher(registration.connection.rule.name, registration.connection.xmlrpc_uri) 365 elif registration.connection.rule.type == SUBSCRIBER: 366 self._unregister_subscriber(node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name) 367 elif registration.connection.rule.type == SERVICE: 368 node_master.unregisterService(registration.connection.rule.name, registration.connection.type_info) 369 elif registration.connection.rule.type == ACTION_SERVER: 370 self._unregister_subscriber(node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/goal") 371 self._unregister_subscriber(node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/cancel") 372 node_master.unregisterPublisher(registration.connection.rule.name + "/status", registration.connection.xmlrpc_uri) 373 node_master.unregisterPublisher(registration.connection.rule.name + "/feedback", registration.connection.xmlrpc_uri) 374 node_master.unregisterPublisher(registration.connection.rule.name + "/result", registration.connection.xmlrpc_uri) 375 elif registration.connection.rule.type == ACTION_CLIENT: 376 node_master.unregisterPublisher(registration.connection.rule.name + "/goal", registration.connection.xmlrpc_uri) 377 node_master.unregisterPublisher(registration.connection.rule.name + "/cancel", registration.connection.xmlrpc_uri) 378 self._unregister_subscriber(node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/status") 379 self._unregister_subscriber(node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/feedback") 380 self._unregister_subscriber(node_master, registration.connection.xmlrpc_uri, registration.connection.rule.name + "/result")
381
382 - def _register_subscriber(self, node_master, name, type_info, xmlrpc_uri):
383 ''' 384 This one is not necessary, since you can pretty much guarantee the 385 existence of the subscriber here, but it pays to be safe - we've seen 386 some errors come out here when the ROS_MASTER_URI was only set to 387 localhost. 388 389 @param node_master : node-master xmlrpc method handler 390 @param type_info : type of the subscriber message 391 @param xmlrpc_uri : the uri of the node (xmlrpc server) 392 @type string 393 @param name : fully resolved subscriber name 394 ''' 395 # This unfortunately is a game breaker - it destroys all connections, not just those 396 # connected to this master, see #125. 397 pub_uri_list = node_master.registerSubscriber(name, type_info, xmlrpc_uri) 398 try: 399 #rospy.loginfo("register_subscriber [%s][%s][%s]" % (name, xmlrpc_uri, pub_uri_list)) 400 xmlrpcapi(xmlrpc_uri).publisherUpdate('/master', name, pub_uri_list) 401 except socket.error, v: 402 errorcode = v[0] 403 if errorcode != errno.ECONNREFUSED: 404 rospy.logerr("Gateway : error registering subscriber (is ROS_MASTER_URI and ROS_HOSTNAME or ROS_IP correctly set?)") 405 rospy.logerr("Gateway : errorcode [%s] xmlrpc_uri [%s]" % (str(errorcode), xmlrpc_uri)) 406 raise # better handling here would be ideal 407 else: 408 pass # subscriber stopped on the other side, don't worry about it
409
410 - def _unregister_subscriber(self, node_master, xmlrpc_uri, name):
411 ''' 412 It is a special case as it requires xmlrpc handling to inform the subscriber of 413 the disappearance of publishers it was connected to. It also needs to handle the 414 case when that information doesn't get to the subscriber because it is down. 415 416 @param node_master : node-master xmlrpc method handler 417 @param xmlrpc_uri : the uri of the node (xmlrpc server) 418 @type string 419 @param name : fully resolved subscriber name 420 ''' 421 # This unfortunately is a game breaker - it destroys all connections, not just those 422 # connected to this master, see #125. 423 try: 424 xmlrpcapi(xmlrpc_uri).publisherUpdate('/master', name, []) 425 except socket.error, v: 426 errorcode = v[0] 427 if errorcode != errno.ECONNREFUSED: 428 raise # better handling here would be ideal 429 else: 430 pass # subscriber stopped on the other side, don't worry about it 431 node_master.unregisterSubscriber(name, xmlrpc_uri)
432 433 ########################################################################## 434 # Master utility methods 435 ########################################################################## 436
437 - def generate_connection_details(self, connection_type, name, node):
438 ''' 439 Creates all the extra details to create a connection object from a 440 rule. 441 442 @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType) 443 @type string 444 @param name : the name of the connection 445 @type string 446 @param node : the master node name it comes from 447 @param string 448 449 @return the utils.Connection object complete with type_info and xmlrpc_uri 450 @type utils.Connection 451 ''' 452 xmlrpc_uri = self.lookupNode(node) 453 connections = [] 454 if connection_type == PUBLISHER or connection_type == SUBSCRIBER: 455 type_info = rostopic.get_topic_type(name)[0] # message type 456 connections.append(utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri)) 457 elif connection_type == SERVICE: 458 type_info = rosservice.get_service_uri(name) 459 connections.append(utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri)) 460 elif connection_type == ACTION_SERVER: 461 type_info = rostopic.get_topic_type(name + '/goal')[0] # message type 462 connections.append(utils.Connection(Rule(SUBSCRIBER, name + '/goal', node), type_info, xmlrpc_uri)) 463 type_info = rostopic.get_topic_type(name + '/cancel')[0] # message type 464 connections.append(utils.Connection(Rule(SUBSCRIBER, name + '/cancel', node), type_info, xmlrpc_uri)) 465 type_info = rostopic.get_topic_type(name + '/status')[0] # message type 466 connections.append(utils.Connection(Rule(PUBLISHER, name + '/status', node), type_info, xmlrpc_uri)) 467 type_info = rostopic.get_topic_type(name + '/feedback')[0] # message type 468 connections.append(utils.Connection(Rule(PUBLISHER, name + '/feedback', node), type_info, xmlrpc_uri)) 469 type_info = rostopic.get_topic_type(name + '/result')[0] # message type 470 connections.append(utils.Connection(Rule(PUBLISHER, name + '/result', node), type_info, xmlrpc_uri)) 471 elif connection_type == ACTION_CLIENT: 472 type_info = rostopic.get_topic_type(name + '/goal')[0] # message type 473 connections.append(utils.Connection(Rule(PUBLISHER, name + '/goal', node), type_info, xmlrpc_uri)) 474 type_info = rostopic.get_topic_type(name + '/cancel')[0] # message type 475 connections.append(utils.Connection(Rule(PUBLISHER, name + '/cancel', node), type_info, xmlrpc_uri)) 476 type_info = rostopic.get_topic_type(name + '/status')[0] # message type 477 connections.append(utils.Connection(Rule(SUBSCRIBER, name + '/status', node), type_info, xmlrpc_uri)) 478 type_info = rostopic.get_topic_type(name + '/feedback')[0] # message type 479 connections.append(utils.Connection(Rule(SUBSCRIBER, name + '/feedback', node), type_info, xmlrpc_uri)) 480 type_info = rostopic.get_topic_type(name + '/result')[0] # message type 481 connections.append(utils.Connection(Rule(SUBSCRIBER, name + '/result', node), type_info, xmlrpc_uri)) 482 return connections
483
484 - def generate_advertisement_connection_details(self, connection_type, name, node):
485 ''' 486 Creates all the extra details to create a connection object from an 487 advertisement rule. This is a bit different to the previous one - we just need 488 the type and single node uri that everything originates from (don't need to generate all 489 the pub/sub connections themselves. 490 491 Probably flips could be merged into this sometime, but it'd be a bit gnarly. 492 493 @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType) 494 @type string 495 @param name : the name of the connection 496 @type string 497 @param node : the master node name it comes from 498 @param string 499 500 @return the utils.Connection object complete with type_info and xmlrpc_uri 501 @type utils.Connection 502 ''' 503 xmlrpc_uri = self.lookupNode(node) 504 if connection_type == PUBLISHER or connection_type == SUBSCRIBER: 505 type_info = rostopic.get_topic_type(name)[0] # message type 506 connection = utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri) 507 elif connection_type == SERVICE: 508 type_info = rosservice.get_service_uri(name) 509 connection = utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri) 510 elif connection_type == ACTION_SERVER or connection_type == ACTION_CLIENT: 511 goal_topic = name + '/goal' 512 goal_topic_type = rostopic.get_topic_type(goal_topic) 513 type_info = re.sub('ActionGoal$', '', goal_topic_type[0]) # Base type for action 514 connection = utils.Connection(Rule(connection_type, name, node), type_info, xmlrpc_uri) 515 return connection
516
517 - def get_ros_ip(self):
518 o = urlparse.urlparse(rosgraph.get_master_uri()) 519 if o.hostname == 'localhost': 520 ros_ip = '' 521 try: 522 ros_ip = os.environ['ROS_IP'] 523 except Exception: 524 try: 525 # often people use this one instead 526 ros_ip = os.environ['ROS_HOSTNAME'] 527 except Exception: 528 # should probably check other means here - e.g. first of the system ipconfig 529 rospy.logwarn("Gateway: no valid ip found for this host, just setting 'localhost'") 530 return 'localhost' 531 return ros_ip 532 else: 533 return o.hostname
534
535 - def get_connection_state(self):
536 unused_new_connections, unused_lost_connections = self._connection_cache.update() 537 # This would be more optimal, but we'll have to perturb lots of code 538 #return new_connections, lost_connections 539 return self._connection_cache._connections
540
541 - def _get_anonymous_node_name(self, topic):
542 t = topic[1:len(topic)] 543 name = roslib.names.anonymous_name(t) 544 return name
545 546 ########################################################################## 547 # Master utility methods for scripts 548 ########################################################################## 549
550 - def find_gateway_namespace(self):
551 ''' 552 Assists a script to find the (hopefully) unique gateway namespace. 553 Note that unique is a necessary condition, there should only be one 554 gateway per ros system. 555 556 @return Namespace of the gateway node. 557 @rtype string 558 ''' 559 unused_publishers, unused_subscribers, services = self.get_system_state() 560 for service in services: 561 service_name = service[0] # second part is the node name 562 if re.search(r'remote_gateway_info', service_name): 563 if service_name == '/remote_gateway_info': 564 return "/" 565 else: 566 return re.sub(r'/remote_gateway_info', '', service_name) 567 return None
568