master_api.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # License: BSD
4 # https://raw.github.com/robotics-in-concert/rocon_multimaster/license/LICENSE
5 #
6 ##############################################################################
7 # Imports
8 ##############################################################################
9 
10 import os
11 import socket
12 import httplib
13 import errno
14 import xmlrpclib
15 from contextlib import contextmanager
16 
17 from rosmaster.util import xmlrpcapi
18 
19 import rocon_python_comms
20 
21 try:
22  import urllib.parse as urlparse # Python 3.x
23 except ImportError:
24  import urlparse
25 import re
26 import threading
27 
28 import rospy
29 import rosgraph
30 import rostopic
31 import rosservice
32 import roslib.names
33 import gateway_msgs.msg as gateway_msgs
34 import rocon_gateway_utils
35 
36 from . import utils, GatewayError
37 
38 
39 class LocalMaster(rosgraph.Master):
40 
41  '''
42  Representing a ros master (local ros master). Just contains a
43  few utility methods for retrieving master related information as well
44  as handles for registering and unregistering rules that have
45  been pulled or flipped in from another gateway.
46  '''
47 
48  def __init__(self, connection_cache_timeout=None):
49  rosgraph.Master.__init__(self, rospy.get_name())
50 
51  timeout = connection_cache_timeout or rospy.Time(30)
52 
53  self.connections_lock = threading.Lock()
54  self.connections = utils.create_empty_connection_type_dictionary(set)
55  # in case this class is used directly (script call) we need to find the connection cache
56 
57  connection_cache_namespace = rocon_gateway_utils.resolve_connection_cache(timeout)
58  if not connection_cache_namespace.endswith('/'):
59  connection_cache_namespace += '/'
60 
61  self.connection_cache = rocon_python_comms.ConnectionCacheProxy(
62  list_sub=connection_cache_namespace + 'connection_cache/list',
63  handle_actions=True,
64  user_callback=self._connection_cache_proxy_cb,
65  diff_opt=True,
66  diff_sub=connection_cache_namespace + 'connection_cache/diff',
67  list_wait_timeout=30 # be generous in timeout in case system is slow to start
68  )
69  self.get_system_state = self.connection_cache.getSystemState
70 
71 
72  ##########################################################################
73  # Registration
74  ##########################################################################
75 
76  def register(self, registration):
77  '''
78  Registers a rule with the local master.
79 
80  @param registration : registration details
81  @type utils.Registration
82 
83  @return the updated registration object (only adds an anonymously generated local node name)
84  @rtype utils.Registration
85  '''
86  # rograph.Master doesn't care whether the node is prefixed with slash or not, but we use it to
87  # compare registrations later in FlippedInterface._is_registration_in_remote_rule()
88  registration.local_node = "/" + self._get_anonymous_node_name(registration.connection.rule.node)
89  rospy.logdebug("Gateway : registering a new node [%s] for [%s]" % (registration.local_node, registration))
90 
91  # Then do we need checkIfIsLocal? Needs lots of parsing time, and the outer class should
92  # already have handle that.
93 
94  node_master = rosgraph.Master(registration.local_node)
95  if registration.connection.rule.type == rocon_python_comms.PUBLISHER:
96  try:
97  node_master.registerPublisher(
98  registration.connection.rule.name,
99  registration.connection.type_info,
100  registration.connection.xmlrpc_uri)
101  return registration
102  except (socket.error, socket.gaierror) as e:
103  rospy.logerr("Gateway : got socket error trying to register a publisher on the local master [%s][%s]" % (
104  registration.connection.rule.name, str(e)))
105  return None
106  except rosgraph.masterapi.Error as e:
107  rospy.logerr("Gateway : got error trying to register a publisher on the local master [%s][%s]" % (
108  registration.connection.rule.name, str(e)))
109  return None
110  except rosgraph.masterapi.Failure as e:
111  rospy.logerr("Gateway : failed to register a publisher on the local master [%s][%s]" % (
112  registration.connection.rule.name, str(e)))
113  return None
114  elif registration.connection.rule.type == rocon_python_comms.SUBSCRIBER:
115  try:
117  node_master,
118  registration.connection.rule.name,
119  registration.connection.type_info,
120  registration.connection.xmlrpc_uri)
121  return registration
122  except (socket.error, socket.gaierror) as e:
123  rospy.logerr("Gateway : got socket error trying to register a subscriber on the local master [%s][%s]" % (
124  registration.connection.rule.name, str(e)))
125  return None
126  except rosgraph.masterapi.Error as e:
127  rospy.logerr("Gateway : got error trying to register a subscriber on the local master [%s][%s]" % (
128  registration.connection.rule.name, str(e)))
129  return None
130  except rosgraph.masterapi.Failure as e:
131  rospy.logerr("Gateway : failed to register a subscriber on the local master [%s][%s]" % (
132  registration.connection.rule.name, str(e)))
133  return None
134  elif registration.connection.rule.type == rocon_python_comms.SERVICE:
135  node_name = rosservice.get_service_node(registration.connection.rule.name)
136  if node_name is not None:
137  rospy.logwarn(
138  "Gateway : tried to register a service that is already locally available, aborting [%s][%s]" %
139  (registration.connection.rule.name, node_name))
140  return None
141  else:
142  if registration.connection.rule.name is None:
143  rospy.logerr(
144  "Gateway : tried to register a service with name set to None [%s, %s, %s]" %
145  (registration.connection.rule.name,
146  registration.connection.type_info,
147  registration.connection.xmlrpc_uri))
148  return None
149  if registration.connection.type_info is None:
150  rospy.logerr(
151  "Gateway : tried to register a service with type_info set to None [%s, %s, %s]" %
152  (registration.connection.rule.name,
153  registration.connection.type_info,
154  registration.connection.xmlrpc_uri))
155  return None
156  if registration.connection.xmlrpc_uri is None:
157  rospy.logerr(
158  "Gateway : tried to register a service with xmlrpc_uri set to None [%s, %s, %s]" %
159  (registration.connection.rule.name,
160  registration.connection.type_info,
161  registration.connection.xmlrpc_uri))
162  return None
163  try:
164  node_master.registerService(
165  registration.connection.rule.name,
166  registration.connection.type_info,
167  registration.connection.xmlrpc_uri)
168  return registration
169  except (socket.error, socket.gaierror) as e:
170  rospy.logerr("Gateway : got socket error trying to register a service on the local master [%s][%s]" % (
171  registration.connection.rule.name, str(e)))
172  return None
173  except rosgraph.masterapi.Error as e:
174  rospy.logerr("Gateway : got error trying to register a service on the local master [%s][%s]" % (
175  registration.connection.rule.name, str(e)))
176  return None
177  except rosgraph.masterapi.Failure as e:
178  rospy.logerr("Gateway : failed to register a service on the local master [%s][%s]" % (
179  registration.connection.rule.name, str(e)))
180  return None
181  elif registration.connection.rule.type == rocon_python_comms.ACTION_SERVER:
182  try:
183  # Need to update these with self._register_subscriber
185  node_master,
186  registration.connection.rule.name +
187  "/goal",
188  registration.connection.type_info +
189  "ActionGoal",
190  registration.connection.xmlrpc_uri)
192  node_master,
193  registration.connection.rule.name +
194  "/cancel",
195  "actionlib_msgs/GoalID",
196  registration.connection.xmlrpc_uri)
197  node_master.registerPublisher(
198  registration.connection.rule.name +
199  "/status",
200  "actionlib_msgs/GoalStatusArray",
201  registration.connection.xmlrpc_uri)
202  node_master.registerPublisher(
203  registration.connection.rule.name +
204  "/feedback",
205  registration.connection.type_info +
206  "ActionFeedback",
207  registration.connection.xmlrpc_uri)
208  node_master.registerPublisher(
209  registration.connection.rule.name +
210  "/result",
211  registration.connection.type_info +
212  "ActionResult",
213  registration.connection.xmlrpc_uri)
214  return registration
215  except (socket.error, socket.gaierror) as e:
216  rospy.logerr("Gateway : got socket error trying to register an action server on the local master [%s][%s]" % (
217  registration.connection.rule.name, str(e)))
218  return None
219  except rosgraph.masterapi.Error as e:
220  rospy.logerr("Gateway : got error trying to register an action server on the local master [%s][%s]" % (
221  registration.connection.rule.name, str(e)))
222  return None
223  except rosgraph.masterapi.Failure as e:
224  rospy.logerr("Gateway : failed to register an action server on the local master [%s][%s]" % (
225  registration.connection.rule.name, str(e)))
226  return None
227  elif registration.connection.rule.type == rocon_python_comms.ACTION_CLIENT:
228  try:
229  node_master.registerPublisher(
230  registration.connection.rule.name +
231  "/goal",
232  registration.connection.type_info +
233  "ActionGoal",
234  registration.connection.xmlrpc_uri)
235  node_master.registerPublisher(
236  registration.connection.rule.name +
237  "/cancel",
238  "actionlib_msgs/GoalID",
239  registration.connection.xmlrpc_uri)
240  self._register_subscriber(node_master, registration.connection.rule.name +
241  "/status", "actionlib_msgs/GoalStatusArray", registration.connection.xmlrpc_uri)
243  node_master,
244  registration.connection.rule.name +
245  "/feedback",
246  registration.connection.type_info +
247  "ActionFeedback",
248  registration.connection.xmlrpc_uri)
250  node_master,
251  registration.connection.rule.name +
252  "/result",
253  registration.connection.type_info +
254  "ActionResult",
255  registration.connection.xmlrpc_uri)
256  return registration
257  except (socket.error, socket.gaierror) as e:
258  rospy.logerr("Gateway : got socket error trying to register an action server on the local master [%s][%s]" % (
259  registration.connection.rule.name, str(e)))
260  return None
261  except rosgraph.masterapi.Error as e:
262  rospy.logerr("Gateway : got error trying to register an action server on the local master [%s][%s]" % (
263  registration.connection.rule.name, str(e)))
264  return None
265  except rosgraph.masterapi.Failure as e:
266  rospy.logerr("Gateway : failed to register an action server on the local master [%s][%s]" % (
267  registration.connection.rule.name, str(e)))
268  return None
269  else:
270  rospy.logerr("Gateway : tried to register unknown rule type [%s]" % (
271  registration.connection.rule.type))
272  return None
273 
274  def unregister(self, registration):
275  '''
276  Unregisters a rule with the local master.
277 
278  @param registration : registration details for an existing gateway registered rule
279  @type utils.Registration
280  '''
281  node_master = rosgraph.Master(registration.local_node)
282  rospy.logdebug("Gateway : unregistering local node [%s] for [%s]" % (registration.local_node, registration))
283  if registration.connection.rule.type == rocon_python_comms.PUBLISHER:
284  try:
285  node_master.unregisterPublisher(registration.connection.rule.name, registration.connection.xmlrpc_uri)
286  except (socket.error, socket.gaierror) as e:
287  rospy.logerr("Gateway : got socket error trying to unregister a publisher on the local master [%s][%s]" % (
288  registration.connection.rule.name, str(e)))
289  except rosgraph.masterapi.Error as e:
290  rospy.logerr("Gateway : got error trying to unregister a publisher on the local master [%s][%s]" % (
291  registration.connection.rule.name, str(e)))
292  except rosgraph.masterapi.Failure as e:
293  rospy.logerr("Gateway : failed to unregister a publisher on the local master [%s][%s]" % (
294  registration.connection.rule.name, str(e)))
295  elif registration.connection.rule.type == rocon_python_comms.SUBSCRIBER:
296  try:
297  node_master.unregisterSubscriber(registration.connection.rule.name, registration.connection.xmlrpc_uri)
298  except (socket.error, socket.gaierror) as e:
299  rospy.logerr("Gateway : got socket error trying to unregister a subscriber on the local master [%s][%s]" % (
300  registration.connection.rule.name, str(e)))
301  except rosgraph.masterapi.Error as e:
302  rospy.logerr("Gateway : got error trying to unregister a subscriber on the local master [%s][%s]" % (
303  registration.connection.rule.name, str(e)))
304  except rosgraph.masterapi.Failure as e:
305  rospy.logerr("Gateway : failed to unregister a subscriber on the local master [%s][%s]" % (
306  registration.connection.rule.name, str(e)))
307  elif registration.connection.rule.type == rocon_python_comms.SERVICE:
308  try:
309  node_master.unregisterService(registration.connection.rule.name, registration.connection.type_info)
310  except (socket.error, socket.gaierror) as e:
311  rospy.logerr("Gateway : got socket error trying to unregister a service on the local master [%s][%s]" % (
312  registration.connection.rule.name, str(e)))
313  except rosgraph.masterapi.Error as e:
314  rospy.logerr("Gateway : got error trying to unregister a service on the local master [%s][%s]" % (
315  registration.connection.rule.name, str(e)))
316  except rosgraph.masterapi.Failure as e:
317  rospy.logerr("Gateway : failed to unregister a service on the local master [%s][%s]" % (
318  registration.connection.rule.name, str(e)))
319  elif registration.connection.rule.type == rocon_python_comms.ACTION_SERVER:
320  try:
321  node_master.unregisterSubscriber(
322  registration.connection.rule.name + "/goal", registration.connection.xmlrpc_uri)
323  node_master.unregisterSubscriber(
324  registration.connection.rule.name + "/cancel", registration.connection.xmlrpc_uri)
325  node_master.unregisterPublisher(
326  registration.connection.rule.name + "/status", registration.connection.xmlrpc_uri)
327  node_master.unregisterPublisher(
328  registration.connection.rule.name + "/feedback", registration.connection.xmlrpc_uri)
329  node_master.unregisterPublisher(
330  registration.connection.rule.name + "/result", registration.connection.xmlrpc_uri)
331  except (socket.error, socket.gaierror) as e:
332  rospy.logerr("Gateway : got socket error trying to unregister an action server on the local master [%s][%s]" % (
333  registration.connection.rule.name, str(e)))
334  except rosgraph.masterapi.Error as e:
335  rospy.logerr("Gateway : got error trying to unregister an action server on the local master [%s][%s]" % (
336  registration.connection.rule.name, str(e)))
337  except rosgraph.masterapi.Failure as e:
338  rospy.logerr("Gateway : failed to unregister an action server on the local master [%s][%s]" % (
339  registration.connection.rule.name, str(e)))
340  elif registration.connection.rule.type == rocon_python_comms.ACTION_CLIENT:
341  try:
342  node_master.unregisterPublisher(
343  registration.connection.rule.name + "/goal", registration.connection.xmlrpc_uri)
344  node_master.unregisterPublisher(
345  registration.connection.rule.name + "/cancel", registration.connection.xmlrpc_uri)
346  node_master.unregisterSubscriber(
347  registration.connection.rule.name + "/status", registration.connection.xmlrpc_uri)
348  node_master.unregisterSubscriber(
349  registration.connection.rule.name + "/feedback", registration.connection.xmlrpc_uri)
350  node_master.unregisterSubscriber(
351  registration.connection.rule.name + "/result", registration.connection.xmlrpc_uri)
352  except (socket.error, socket.gaierror) as e:
353  rospy.logerr("Gateway : got socket error trying to unregister an action client on the local master [%s][%s]" % (
354  registration.connection.rule.name, str(e)))
355  except rosgraph.masterapi.Error as e:
356  rospy.logerr("Gateway : got error trying to unregister an action client on the local master [%s][%s]" % (
357  registration.connection.rule.name, str(e)))
358  except rosgraph.masterapi.Failure as e:
359  rospy.logerr("Gateway : failed to unregister an action client on the local master [%s][%s]" % (
360  registration.connection.rule.name, str(e)))
361 
362  def _register_subscriber(self, node_master, name, type_info, xmlrpc_uri):
363  '''
364  This one is not necessary, since you can pretty much guarantee the
365  existence of the subscriber here, but it pays to be safe - we've seen
366  some errors come out here when the ROS_MASTER_URI was only set to
367  localhost.
368 
369  @param node_master : node-master xmlrpc method handler
370  @param type_info : type of the subscriber message
371  @param xmlrpc_uri : the uri of the node (xmlrpc server)
372  @type string
373  @param name : fully resolved subscriber name
374  '''
375  # This unfortunately is a game breaker - it destroys all connections, not just those
376  # connected to this master, see #125.
377  pub_uri_list = node_master.registerSubscriber(name, type_info, xmlrpc_uri)
378  # Be nice to the subscriber, inform it that is should refresh it's publisher list.
379  try:
380  rospy.loginfo(
381  "resetting publishers for this node's subscriber [%s][%s][%s]" % (name, xmlrpc_uri, pub_uri_list))
382  # this publisherUpdate will overwrite any other publisher currently known by the subscriber
383  xmlrpcapi(xmlrpc_uri).publisherUpdate('/master', name, pub_uri_list)
384 
385  except (socket.error, socket.gaierror) as v:
386  errorcode = v[0]
387  if errorcode != errno.ECONNREFUSED:
388  rospy.logerr(
389  "Gateway : error registering subscriber " +
390  "(is ROS_MASTER_URI and ROS_HOSTNAME or ROS_IP correctly set?)")
391  rospy.logerr("Gateway : errorcode [%s] xmlrpc_uri [%s]" % (str(errorcode), xmlrpc_uri))
392  raise # better handling here would be ideal
393  else:
394  pass
395  # subscriber stopped on the other side, so don't worry about telling it to 'refresh' its publishers
396  except xmlrpclib.Fault as e:
397  # as above with the socket error, don't worry about telling it to 'refresh' its publishers
398  rospy.logerr("Gateway : serious fault while communicating with a subscriber - its xmlrpc server was around but in a bad state [%s]" % str(e))
399  rospy.logerr("Gateway : if this happened, add to the collected information gathered at https://github.com/robotics-in-concert/rocon_multimaster/issues/304")
400 
401  ##########################################################################
402  # Master utility methods
403  ##########################################################################
404 
405  def generate_connection_details(self, connection_type, name, node):
406  """
407  Creates all the extra details to create a connection object from a
408  rule.
409 
410  @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType)
411  @type string
412  @param name : the name of the connection
413  @type string
414  @param node : the master node name it comes from
415  @param string
416 
417  @return the utils.Connection object complete with type_info and xmlrpc_uri
418  @type utils.Connection
419  """
420  # Very important here to check for the results of xmlrpc_uri and especially topic_type
421  # https://github.com/robotics-in-concert/rocon_multimaster/issues/173
422  # In the watcher thread, we get the local connection index (whereby the arguments of this function
423  # come from) via master.get_connection_state. That means there is a small amount of time from
424  # getting the topic name, to checking for hte xmlrpc_uri and especially topic_type here in which
425  # the topic could have disappeared. When this happens, it returns None.
426  connections = []
427  xmlrpc_uri = node.split(",")[1]
428  node = node.split(",")[0]
429 
430  if xmlrpc_uri is None:
431  return connections
432  if connection_type == rocon_python_comms.PUBLISHER or connection_type == rocon_python_comms.SUBSCRIBER:
433  type_info = rostopic.get_topic_type(name)[0] # message type
434  if type_info is not None:
435  connections.append(utils.Connection(gateway_msgs.Rule(connection_type, name, node), type_info, type_info, xmlrpc_uri))
436  else:
437  rospy.logwarn('Gateway : [%s] does not have type_info. Cannot flip' % name)
438  elif connection_type == rocon_python_comms.SERVICE:
439  type_info = rosservice.get_service_uri(name)
440  type_msg = rosservice.get_service_type(name)
441  if type_info is not None:
442  connections.append(utils.Connection(gateway_msgs.Rule(connection_type, name, node), type_msg, type_info, xmlrpc_uri))
443  elif connection_type == rocon_python_comms.ACTION_SERVER:
444  goal_type_info = rostopic.get_topic_type(name + '/goal')[0] # message type
445  cancel_type_info = rostopic.get_topic_type(name + '/cancel')[0] # message type
446  status_type_info = rostopic.get_topic_type(name + '/status')[0] # message type
447  feedback_type_info = rostopic.get_topic_type(name + '/feedback')[0] # message type
448  result_type_info = rostopic.get_topic_type(name + '/result')[0] # message type
449  if (
450  goal_type_info is not None and cancel_type_info is not None and
451  status_type_info is not None and feedback_type_info is not None and
452  result_type_info is not None
453  ):
454  connections.append(utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/goal', node), goal_type_info, goal_type_info, xmlrpc_uri))
455  connections.append(
456  utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/cancel', node), cancel_type_info, cancel_type_info, xmlrpc_uri))
457  connections.append(
458  utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/status', node), status_type_info, status_type_info, xmlrpc_uri))
459  connections.append(
460  utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/feedback', node), feedback_type_info, feedback_type_info, xmlrpc_uri))
461  connections.append(
462  utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/result', node), result_type_info, result_type_info, xmlrpc_uri))
463  elif connection_type == rocon_python_comms.ACTION_CLIENT:
464  goal_type_info = rostopic.get_topic_type(name + '/goal')[0] # message type
465  cancel_type_info = rostopic.get_topic_type(name + '/cancel')[0] # message type
466  status_type_info = rostopic.get_topic_type(name + '/status')[0] # message type
467  feedback_type_info = rostopic.get_topic_type(name + '/feedback')[0] # message type
468  result_type_info = rostopic.get_topic_type(name + '/result')[0] # message type
469  if (
470  goal_type_info is not None and cancel_type_info is not None and
471  status_type_info is not None and feedback_type_info is not None and
472  result_type_info is not None
473  ):
474  connections.append(utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/goal', node), goal_type_info, goal_type_info, xmlrpc_uri))
475  connections.append(
476  utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/cancel', node), cancel_type_info, cancel_type_info, xmlrpc_uri))
477  connections.append(
478  utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/status', node), status_type_info, status_type_info, xmlrpc_uri))
479  connections.append(
480  utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/feedback', node), feedback_type_info, feedback_type_info, xmlrpc_uri))
481  connections.append(
482  utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/result', node), result_type_info, result_type_info, xmlrpc_uri))
483  return connections
484 
485  def generate_advertisement_connection_details(self, connection_type, name, node):
486  '''
487  Creates all the extra details to create a connection object from an
488  advertisement rule. This is a bit different to the previous one - we just need
489  the type and single node uri that everything originates from (don't need to generate all
490  the pub/sub connections themselves.
491 
492  Probably flips could be merged into this sometime, but it'd be a bit gnarly.
493 
494  @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType)
495  @type string
496  @param name : the name of the connection
497  @type string
498  @param node : the master node name it comes from
499  @param string
500 
501  @return the utils.Connection object complete with type_info and xmlrpc_uri
502  @type utils.Connection
503  '''
504  # Very important here to check for the results of xmlrpc_uri and especially topic_type
505  # https://github.com/robotics-in-concert/rocon_multimaster/issues/173
506  # In the watcher thread, we get the local connection index (whereby the arguments of this function
507  # come from) via master.get_connection_state. That means there is a small amount of time from
508  # getting the topic name, to checking for hte xmlrpc_uri and especially topic_type here in which
509  # the topic could have disappeared. When this happens, it returns None.
510  connection = None
511  xmlrpc_uri = self.lookupNode(node)
512  if xmlrpc_uri is None:
513  return connection
514  if connection_type == rocon_python_comms.PUBLISHER or connection_type == rocon_python_comms.SUBSCRIBER:
515  type_info = rostopic.get_topic_type(name)[0] # message type
516  if type_info is not None:
517  connection = utils.Connection(gateway_msgs.Rule(connection_type, name, node), type_info, type_info, xmlrpc_uri)
518  elif connection_type == rocon_python_comms.SERVICE:
519  type_info = rosservice.get_service_uri(name)
520  type_msg = rosservice.get_service_type(name)
521  if type_info is not None:
522  connection = utils.Connection(gateway_msgs.Rule(connection_type, name, node), type_msg, type_info, xmlrpc_uri)
523  elif connection_type == rocon_python_comms.ACTION_SERVER or connection_type == rocon_python_comms.ACTION_CLIENT:
524  goal_topic = name + '/goal'
525  goal_topic_type = rostopic.get_topic_type(goal_topic)
526  type_info = re.sub('ActionGoal$', '', goal_topic_type[0]) # Base type for action
527  if type_info is not None:
528  connection = utils.Connection(gateway_msgs.Rule(connection_type, name, node), type_info, type_info, xmlrpc_uri)
529  return connection
530 
531  def get_ros_ip(self):
532  o = urlparse.urlparse(rosgraph.get_master_uri())
533  if o.hostname == 'localhost':
534  ros_ip = ''
535  try:
536  ros_ip = os.environ['ROS_IP']
537  except Exception:
538  try:
539  # often people use this one instead
540  ros_ip = os.environ['ROS_HOSTNAME']
541  except Exception:
542  # should probably check other means here - e.g. first of the system ipconfig
543  rospy.logwarn("Gateway : no valid ip found for this host, just setting 'localhost'")
544  return 'localhost'
545  return ros_ip
546  else:
547  return o.hostname
548 
549  @staticmethod
550  def _is_topic_node_in_list(topic, node, topic_node_list):
551  # TODO : there is probably a oneliner equivalent for this
552  # check if cancel available
553  available = False
554  for candidate in topic_node_list:
555  if candidate[0] == topic and node in candidate[1]:
556  available = True
557  break
558 
559  @staticmethod
561  t = topic[1:len(topic)]
562  name = roslib.names.anonymous_name(t)
563  return name
564 
565  def _connection_cache_proxy_cb(self, system_state, added_system_state, lost_system_state):
566 
567  self.connections_lock.acquire()
568  # if there was no change but we got a callback,
569  # it means it s the first and we need to set the whole list
570  if added_system_state is None and lost_system_state is None:
571  self.connections[gateway_msgs.ConnectionType.ACTION_SERVER] =\
572  utils._get_connections_from_action_chan_dict(
573  system_state.action_servers, gateway_msgs.ConnectionType.ACTION_SERVER
574  )
575  self.connections[gateway_msgs.ConnectionType.ACTION_CLIENT] =\
576  utils._get_connections_from_action_chan_dict(
577  system_state.action_clients, gateway_msgs.ConnectionType.ACTION_CLIENT
578  )
579  self.connections[gateway_msgs.ConnectionType.PUBLISHER] =\
580  utils._get_connections_from_pub_sub_chan_dict(
581  system_state.publishers, gateway_msgs.ConnectionType.PUBLISHER
582  )
583  self.connections[gateway_msgs.ConnectionType.SUBSCRIBER] =\
584  utils._get_connections_from_pub_sub_chan_dict(
585  system_state.subscribers, gateway_msgs.ConnectionType.SUBSCRIBER
586  )
587  self.connections[gateway_msgs.ConnectionType.SERVICE] =\
588  utils._get_connections_from_service_chan_dict(
589  system_state.services, gateway_msgs.ConnectionType.SERVICE
590  )
591  else: # we got some diff, we can optimize
592  # this is not really needed as is ( since the list we get is always updated )
593  # However it is a first step towards an optimized gateway that can work with system state differences
594  new_action_servers = utils._get_connections_from_action_chan_dict(
595  added_system_state.action_servers, gateway_msgs.ConnectionType.ACTION_SERVER
596  )
597  self.connections[gateway_msgs.ConnectionType.ACTION_SERVER] |= new_action_servers
598 
599  new_action_clients = utils._get_connections_from_action_chan_dict(
600  added_system_state.action_clients, gateway_msgs.ConnectionType.ACTION_CLIENT
601  )
602  self.connections[gateway_msgs.ConnectionType.ACTION_CLIENT] |= new_action_clients
603 
604  new_publishers = utils._get_connections_from_pub_sub_chan_dict(
605  added_system_state.publishers, gateway_msgs.ConnectionType.PUBLISHER
606  )
607  self.connections[gateway_msgs.ConnectionType.PUBLISHER] |= new_publishers
608 
609  new_subscribers = utils._get_connections_from_pub_sub_chan_dict(
610  added_system_state.subscribers, gateway_msgs.ConnectionType.SUBSCRIBER
611  )
612  self.connections[gateway_msgs.ConnectionType.SUBSCRIBER] |= new_subscribers
613 
614  new_services = utils._get_connections_from_service_chan_dict(
615  added_system_state.services, gateway_msgs.ConnectionType.SERVICE
616  )
617  self.connections[gateway_msgs.ConnectionType.SERVICE] |= new_services
618 
619 
620  lost_action_servers = utils._get_connections_from_action_chan_dict(
621  lost_system_state.action_servers, gateway_msgs.ConnectionType.ACTION_SERVER
622  )
623  self.connections[gateway_msgs.ConnectionType.ACTION_SERVER] -= lost_action_servers
624 
625  lost_action_clients = utils._get_connections_from_action_chan_dict(
626  lost_system_state.action_clients, gateway_msgs.ConnectionType.ACTION_CLIENT
627  )
628  self.connections[gateway_msgs.ConnectionType.ACTION_CLIENT] -= lost_action_clients
629 
630  lost_publishers = utils._get_connections_from_pub_sub_chan_dict(
631  lost_system_state.publishers, gateway_msgs.ConnectionType.PUBLISHER
632  )
633  self.connections[gateway_msgs.ConnectionType.PUBLISHER] -= lost_publishers
634 
635  lost_subscribers = utils._get_connections_from_pub_sub_chan_dict(
636  lost_system_state.subscribers, gateway_msgs.ConnectionType.SUBSCRIBER
637  )
638  self.connections[gateway_msgs.ConnectionType.SUBSCRIBER] -= lost_subscribers
639 
640  lost_services = utils._get_connections_from_service_chan_dict(
641  lost_system_state.services, gateway_msgs.ConnectionType.SERVICE
642  )
643  self.connections[gateway_msgs.ConnectionType.SERVICE] -= lost_services
644 
645  self.connections_lock.release()
646 
647  @contextmanager
649  self.connections_lock.acquire()
650  yield self.connections
651  self.connections_lock.release()
652 
def generate_connection_details(self, connection_type, name, node)
Master utility methods.
Definition: master_api.py:405
def register(self, registration)
Registration.
Definition: master_api.py:76
def _is_topic_node_in_list(topic, node, topic_node_list)
Definition: master_api.py:550
def _connection_cache_proxy_cb(self, system_state, added_system_state, lost_system_state)
Definition: master_api.py:565
def generate_advertisement_connection_details(self, connection_type, name, node)
Definition: master_api.py:485
def __init__(self, connection_cache_timeout=None)
Definition: master_api.py:48
def unregister(self, registration)
Definition: master_api.py:274
def _register_subscriber(self, node_master, name, type_info, xmlrpc_uri)
Definition: master_api.py:362


rocon_gateway
Author(s): Daniel Stonier , Jihoon Lee , Piyush Khandelwal
autogenerated on Mon Jun 10 2019 14:40:10