13 import gateway_msgs.msg
as gateway_msgs
14 import rocon_python_comms
25 @param timeout : timeout on checking for the gateway, if None, it just makes a single attempt. 26 @type rospy.rostime.Duration 28 @raise rocon_python_comms.NotFoundException: if no remote gateways or no matching gateways available. 30 gateway_namespace =
None 32 timeout_time = time.time() + timeout.to_sec()
if timeout
is not None else None 33 while not rospy.is_shutdown():
34 if timeout_time
is not None and time.time() > timeout_time:
36 service_names = rosservice.rosservice_find(
"gateway_msgs/RemoteGatewayInfo")
37 if not service_names
or len(service_names) > 1:
38 gateway_namespace =
None 39 elif service_names[0] ==
'/remote_gateway_info':
40 gateway_namespace =
"/" 42 gateway_namespace = re.sub(
r'/remote_gateway_info',
'', service_names[0])
43 if gateway_namespace
is not None or timeout
is None:
46 rospy.rostime.wallsleep(0.1)
47 if not gateway_namespace:
49 raise rocon_python_comms.NotFoundException(
"no gateway found attached to this local master - did you start it?")
51 raise rocon_python_comms.NotFoundException(
"found more than one gateway connected to this master, this is an invalid configuration.")
53 return gateway_namespace
58 @param timeout : timeout on checking for the connection_cache, if None, it just makes a single attempt. 59 @type rospy.rostime.Duration 61 @raise rocon_python_comms.NotFoundException: if no connection_cache available. 63 connection_cache_namespace =
None 65 timeout_time = time.time() + timeout.to_sec()
if timeout
is not None else None 66 while not rospy.is_shutdown():
67 if timeout_time
is not None and time.time() > timeout_time:
70 topic_names = rostopic.find_by_type(
"rocon_std_msgs/ConnectionsList")
71 if not topic_names
or len(topic_names) > 1:
72 connection_cache_namespace =
None 73 elif topic_names[0] ==
'/connection_cache/list':
74 connection_cache_namespace =
"/" 76 connection_cache_namespace = re.sub(
r'/connection_cache/list',
'', topic_names[0])
77 if connection_cache_namespace
is not None or timeout
is None:
80 rospy.rostime.wallsleep(0.1)
81 if not connection_cache_namespace:
83 raise rocon_python_comms.NotFoundException(
"no connection_cache found attached to this local master - did you start it?")
85 raise rocon_python_comms.NotFoundException(
"found more than one connection_cache connected to this master, this is an invalid configuration.")
87 return connection_cache_namespace
92 @param the local topic namespace to prepend to the 'gateway_info' identifier. Uses 93 resolve_local_gateway if none is specified. 96 @return the local gateway info in all its gory detail. 97 @rtype gateway_msgs.GatewayInfo 99 @raise rocon_gateway.GatewayError: if no remote gateways or no matching gateways available. 101 if gateway_namespace ==
None:
103 gateway_info = rocon_python_comms.SubscriberProxy(gateway_namespace +
'/gateway_info', gateway_msgs.GatewayInfo)()
def resolve_gateway_info(gateway_namespace=None)
def resolve_connection_cache(timeout=None)
def resolve_local_gateway(timeout=None)
Gateway Existence.