15 from contextlib
import contextmanager
17 from rosmaster.util
import xmlrpcapi
19 import rocon_python_comms
22 import urllib.parse
as urlparse
33 import gateway_msgs.msg
as gateway_msgs
34 import rocon_gateway_utils
36 from .
import utils, GatewayError
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. 48 def __init__(self, connection_cache_timeout=None):
49 rosgraph.Master.__init__(self, rospy.get_name())
51 timeout = connection_cache_timeout
or rospy.Time(30)
54 self.
connections = utils.create_empty_connection_type_dictionary(set)
57 connection_cache_namespace = rocon_gateway_utils.resolve_connection_cache(timeout)
58 if not connection_cache_namespace.endswith(
'/'):
59 connection_cache_namespace +=
'/' 62 list_sub=connection_cache_namespace +
'connection_cache/list',
66 diff_sub=connection_cache_namespace +
'connection_cache/diff',
78 Registers a rule with the local master. 80 @param registration : registration details 81 @type utils.Registration 83 @return the updated registration object (only adds an anonymously generated local node name) 84 @rtype utils.Registration 89 rospy.logdebug(
"Gateway : registering a new node [%s] for [%s]" % (registration.local_node, registration))
94 node_master = rosgraph.Master(registration.local_node)
95 if registration.connection.rule.type == rocon_python_comms.PUBLISHER:
97 node_master.registerPublisher(
98 registration.connection.rule.name,
99 registration.connection.type_info,
100 registration.connection.xmlrpc_uri)
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)))
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)))
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)))
114 elif registration.connection.rule.type == rocon_python_comms.SUBSCRIBER:
118 registration.connection.rule.name,
119 registration.connection.type_info,
120 registration.connection.xmlrpc_uri)
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)))
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)))
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)))
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:
138 "Gateway : tried to register a service that is already locally available, aborting [%s][%s]" %
139 (registration.connection.rule.name, node_name))
142 if registration.connection.rule.name
is None:
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))
149 if registration.connection.type_info
is None:
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))
156 if registration.connection.xmlrpc_uri
is None:
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))
164 node_master.registerService(
165 registration.connection.rule.name,
166 registration.connection.type_info,
167 registration.connection.xmlrpc_uri)
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)))
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)))
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)))
181 elif registration.connection.rule.type == rocon_python_comms.ACTION_SERVER:
186 registration.connection.rule.name +
188 registration.connection.type_info +
190 registration.connection.xmlrpc_uri)
193 registration.connection.rule.name +
195 "actionlib_msgs/GoalID",
196 registration.connection.xmlrpc_uri)
197 node_master.registerPublisher(
198 registration.connection.rule.name +
200 "actionlib_msgs/GoalStatusArray",
201 registration.connection.xmlrpc_uri)
202 node_master.registerPublisher(
203 registration.connection.rule.name +
205 registration.connection.type_info +
207 registration.connection.xmlrpc_uri)
208 node_master.registerPublisher(
209 registration.connection.rule.name +
211 registration.connection.type_info +
213 registration.connection.xmlrpc_uri)
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)))
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)))
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)))
227 elif registration.connection.rule.type == rocon_python_comms.ACTION_CLIENT:
229 node_master.registerPublisher(
230 registration.connection.rule.name +
232 registration.connection.type_info +
234 registration.connection.xmlrpc_uri)
235 node_master.registerPublisher(
236 registration.connection.rule.name +
238 "actionlib_msgs/GoalID",
239 registration.connection.xmlrpc_uri)
241 "/status",
"actionlib_msgs/GoalStatusArray", registration.connection.xmlrpc_uri)
244 registration.connection.rule.name +
246 registration.connection.type_info +
248 registration.connection.xmlrpc_uri)
251 registration.connection.rule.name +
253 registration.connection.type_info +
255 registration.connection.xmlrpc_uri)
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)))
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)))
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)))
270 rospy.logerr(
"Gateway : tried to register unknown rule type [%s]" % (
271 registration.connection.rule.type))
276 Unregisters a rule with the local master. 278 @param registration : registration details for an existing gateway registered rule 279 @type utils.Registration 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:
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:
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:
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:
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:
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)))
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 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) 373 @param name : fully resolved subscriber name 377 pub_uri_list = node_master.registerSubscriber(name, type_info, xmlrpc_uri)
381 "resetting publishers for this node's subscriber [%s][%s][%s]" % (name, xmlrpc_uri, pub_uri_list))
383 xmlrpcapi(xmlrpc_uri).publisherUpdate(
'/master', name, pub_uri_list)
385 except (socket.error, socket.gaierror)
as v:
387 if errorcode != errno.ECONNREFUSED:
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))
396 except xmlrpclib.Fault
as e:
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")
407 Creates all the extra details to create a connection object from a 410 @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType) 412 @param name : the name of the connection 414 @param node : the master node name it comes from 417 @return the utils.Connection object complete with type_info and xmlrpc_uri 418 @type utils.Connection 427 xmlrpc_uri = node.split(
",")[1]
428 node = node.split(
",")[0]
430 if xmlrpc_uri
is None:
432 if connection_type == rocon_python_comms.PUBLISHER
or connection_type == rocon_python_comms.SUBSCRIBER:
433 type_info = rostopic.get_topic_type(name)[0]
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))
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]
445 cancel_type_info = rostopic.get_topic_type(name +
'/cancel')[0]
446 status_type_info = rostopic.get_topic_type(name +
'/status')[0]
447 feedback_type_info = rostopic.get_topic_type(name +
'/feedback')[0]
448 result_type_info = rostopic.get_topic_type(name +
'/result')[0]
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 454 connections.append(
utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name +
'/goal', node), goal_type_info, goal_type_info, xmlrpc_uri))
456 utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name +
'/cancel', node), cancel_type_info, cancel_type_info, xmlrpc_uri))
458 utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name +
'/status', node), status_type_info, status_type_info, xmlrpc_uri))
460 utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name +
'/feedback', node), feedback_type_info, feedback_type_info, xmlrpc_uri))
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]
465 cancel_type_info = rostopic.get_topic_type(name +
'/cancel')[0]
466 status_type_info = rostopic.get_topic_type(name +
'/status')[0]
467 feedback_type_info = rostopic.get_topic_type(name +
'/feedback')[0]
468 result_type_info = rostopic.get_topic_type(name +
'/result')[0]
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 474 connections.append(
utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name +
'/goal', node), goal_type_info, goal_type_info, xmlrpc_uri))
476 utils.Connection(gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name +
'/cancel', node), cancel_type_info, cancel_type_info, xmlrpc_uri))
478 utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name +
'/status', node), status_type_info, status_type_info, xmlrpc_uri))
480 utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name +
'/feedback', node), feedback_type_info, feedback_type_info, xmlrpc_uri))
482 utils.Connection(gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name +
'/result', node), result_type_info, result_type_info, xmlrpc_uri))
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. 492 Probably flips could be merged into this sometime, but it'd be a bit gnarly. 494 @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType) 496 @param name : the name of the connection 498 @param node : the master node name it comes from 501 @return the utils.Connection object complete with type_info and xmlrpc_uri 502 @type utils.Connection 511 xmlrpc_uri = self.lookupNode(node)
512 if xmlrpc_uri
is None:
514 if connection_type == rocon_python_comms.PUBLISHER
or connection_type == rocon_python_comms.SUBSCRIBER:
515 type_info = rostopic.get_topic_type(name)[0]
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])
527 if type_info
is not None:
528 connection =
utils.Connection(gateway_msgs.Rule(connection_type, name, node), type_info, type_info, xmlrpc_uri)
532 o = urlparse.urlparse(rosgraph.get_master_uri())
533 if o.hostname ==
'localhost':
536 ros_ip = os.environ[
'ROS_IP']
540 ros_ip = os.environ[
'ROS_HOSTNAME']
543 rospy.logwarn(
"Gateway : no valid ip found for this host, just setting 'localhost'")
554 for candidate
in topic_node_list:
555 if candidate[0] == topic
and node
in candidate[1]:
561 t = topic[1:len(topic)]
562 name = roslib.names.anonymous_name(t)
567 self.connections_lock.acquire()
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
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
579 self.
connections[gateway_msgs.ConnectionType.PUBLISHER] =\
580 utils._get_connections_from_pub_sub_chan_dict(
581 system_state.publishers, gateway_msgs.ConnectionType.PUBLISHER
583 self.
connections[gateway_msgs.ConnectionType.SUBSCRIBER] =\
584 utils._get_connections_from_pub_sub_chan_dict(
585 system_state.subscribers, gateway_msgs.ConnectionType.SUBSCRIBER
587 self.
connections[gateway_msgs.ConnectionType.SERVICE] =\
588 utils._get_connections_from_service_chan_dict(
589 system_state.services, gateway_msgs.ConnectionType.SERVICE
594 new_action_servers = utils._get_connections_from_action_chan_dict(
595 added_system_state.action_servers, gateway_msgs.ConnectionType.ACTION_SERVER
597 self.
connections[gateway_msgs.ConnectionType.ACTION_SERVER] |= new_action_servers
599 new_action_clients = utils._get_connections_from_action_chan_dict(
600 added_system_state.action_clients, gateway_msgs.ConnectionType.ACTION_CLIENT
602 self.
connections[gateway_msgs.ConnectionType.ACTION_CLIENT] |= new_action_clients
604 new_publishers = utils._get_connections_from_pub_sub_chan_dict(
605 added_system_state.publishers, gateway_msgs.ConnectionType.PUBLISHER
607 self.
connections[gateway_msgs.ConnectionType.PUBLISHER] |= new_publishers
609 new_subscribers = utils._get_connections_from_pub_sub_chan_dict(
610 added_system_state.subscribers, gateway_msgs.ConnectionType.SUBSCRIBER
612 self.
connections[gateway_msgs.ConnectionType.SUBSCRIBER] |= new_subscribers
614 new_services = utils._get_connections_from_service_chan_dict(
615 added_system_state.services, gateway_msgs.ConnectionType.SERVICE
617 self.
connections[gateway_msgs.ConnectionType.SERVICE] |= new_services
620 lost_action_servers = utils._get_connections_from_action_chan_dict(
621 lost_system_state.action_servers, gateway_msgs.ConnectionType.ACTION_SERVER
623 self.
connections[gateway_msgs.ConnectionType.ACTION_SERVER] -= lost_action_servers
625 lost_action_clients = utils._get_connections_from_action_chan_dict(
626 lost_system_state.action_clients, gateway_msgs.ConnectionType.ACTION_CLIENT
628 self.
connections[gateway_msgs.ConnectionType.ACTION_CLIENT] -= lost_action_clients
630 lost_publishers = utils._get_connections_from_pub_sub_chan_dict(
631 lost_system_state.publishers, gateway_msgs.ConnectionType.PUBLISHER
633 self.
connections[gateway_msgs.ConnectionType.PUBLISHER] -= lost_publishers
635 lost_subscribers = utils._get_connections_from_pub_sub_chan_dict(
636 lost_system_state.subscribers, gateway_msgs.ConnectionType.SUBSCRIBER
638 self.
connections[gateway_msgs.ConnectionType.SUBSCRIBER] -= lost_subscribers
640 lost_services = utils._get_connections_from_service_chan_dict(
641 lost_system_state.services, gateway_msgs.ConnectionType.SERVICE
643 self.
connections[gateway_msgs.ConnectionType.SERVICE] -= lost_services
645 self.connections_lock.release()
649 self.connections_lock.acquire()
651 self.connections_lock.release()
def get_connection_state(self)
def generate_connection_details(self, connection_type, name, node)
Master utility methods.
def register(self, registration)
Registration.
def _is_topic_node_in_list(topic, node, topic_node_list)
def _connection_cache_proxy_cb(self, system_state, added_system_state, lost_system_state)
def generate_advertisement_connection_details(self, connection_type, name, node)
def __init__(self, connection_cache_timeout=None)
def unregister(self, registration)
def _get_anonymous_node_name(topic)
def _register_subscriber(self, node_master, name, type_info, xmlrpc_uri)