def generate_advertisement_connection_details(self, connection_type, name, node): ''' Creates all the extra details to create a connection object from an advertisement rule. This is a bit different to the previous one - we just need the type and single node uri that everything originates from (don't need to generate all the pub/sub connections themselves. Probably flips could be merged into this sometime, but it'd be a bit gnarly. @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType) @type string @param name : the name of the connection @type string @param node : the master node name it comes from @param string @return the utils.Connection object complete with type_info and xmlrpc_uri @type utils.Connection ''' # Very important here to check for the results of xmlrpc_uri and especially topic_type # https://github.com/robotics-in-concert/rocon_multimaster/issues/173 # In the watcher thread, we get the local connection index (whereby the arguments of this function # come from) via master.get_connection_state. That means there is a small amount of time from # getting the topic name, to checking for hte xmlrpc_uri and especially topic_type here in which # the topic could have disappeared. When this happens, it returns None. connection = None xmlrpc_uri = self.lookupNode(node) if xmlrpc_uri is None: return connection if connection_type == rocon_python_comms.PUBLISHER or connection_type == rocon_python_comms.SUBSCRIBER: type_info = rostopic.get_topic_type(name)[0] # message type if type_info is not None: connection = utils.Connection( gateway_msgs.Rule(connection_type, name, node), type_info, type_info, xmlrpc_uri) elif connection_type == rocon_python_comms.SERVICE: type_info = rosservice.get_service_uri(name) type_msg = rosservice.get_service_type(name) if type_info is not None: connection = utils.Connection( gateway_msgs.Rule(connection_type, name, node), type_msg, type_info, xmlrpc_uri) elif connection_type == rocon_python_comms.ACTION_SERVER or connection_type == rocon_python_comms.ACTION_CLIENT: goal_topic = name + '/goal' goal_topic_type = rostopic.get_topic_type(goal_topic) type_info = re.sub('ActionGoal$', '', goal_topic_type[0]) # Base type for action if type_info is not None: connection = utils.Connection( gateway_msgs.Rule(connection_type, name, node), type_info, type_info, xmlrpc_uri) return connection
def remote_gateway_info(self, gateway): ''' Return remote gateway information for the specified gateway string id. @param gateways : gateway id string to search for @type string @return remote gateway information @rtype gateway_msgs.RemotGateway or None ''' firewall = self._redis_server.get( hub_api.create_rocon_gateway_key(gateway, 'firewall')) ip = self._redis_server.get( hub_api.create_rocon_gateway_key(gateway, 'ip')) if firewall is None: return None # equivalent to saying no gateway of this id found else: remote_gateway = gateway_msgs.RemoteGateway() remote_gateway.name = gateway remote_gateway.ip = ip remote_gateway.firewall = True if int(firewall) else False remote_gateway.public_interface = [] encoded_advertisements = self._redis_server.smembers( hub_api.create_rocon_gateway_key(gateway, 'advertisements')) for encoded_advertisement in encoded_advertisements: advertisement = utils.deserialize_connection( encoded_advertisement) remote_gateway.public_interface.append(advertisement.rule) remote_gateway.flipped_interface = [] encoded_flips = self._redis_server.smembers( hub_api.create_rocon_gateway_key(gateway, 'flips')) for encoded_flip in encoded_flips: [target_gateway, name, connection_type, node] = utils.deserialize(encoded_flip) remote_rule = gateway_msgs.RemoteRule( target_gateway, gateway_msgs.Rule(connection_type, name, node)) remote_gateway.flipped_interface.append(remote_rule) remote_gateway.pulled_interface = [] encoded_pulls = self._redis_server.smembers( hub_api.create_rocon_gateway_key(gateway, 'pulls')) for encoded_pull in encoded_pulls: [target_gateway, name, connection_type, node] = utils.deserialize(encoded_pull) remote_rule = gateway_msgs.RemoteRule( target_gateway, gateway_msgs.Rule(connection_type, name, node)) remote_gateway.pulled_interface.append(remote_rule) return remote_gateway
def deserialize_connection(connection_str): deserialized_list = deserialize(connection_str) rule = gateway_msgs.Rule(deserialized_list[0], deserialized_list[1], deserialized_list[2] ) return Connection(rule, deserialized_list[3], deserialized_list[4], deserialized_list[5])
def pull_tutorials(remote_gateway_name=None, cancel=False, regex_patterns=False, ns=_gateway_namespace): rospy.wait_for_service(ns + '/pull') pull = rospy.ServiceProxy(ns + '/pull', gateway_srvs.Remote) if not remote_gateway_name: remote_gateway_name = find_first_remote_gateway() req = gateway_srvs.RemoteRequest() req.cancel = cancel if regex_patterns: names, nodes = create_tutorial_dictionaries(use_regex_patterns=True) else: names, nodes = create_tutorial_dictionaries(use_regex_patterns=False) req.remotes = [] for connection_type in connection_types: rule = gateway_msgs.Rule() rule.name = names[connection_type] rule.type = connection_type rule.node = nodes[connection_type] rospy.loginfo( "Pull : %s [%s,%s,%s][%s]." % (_action_text(cancel, 'sending pull rule to the gateway'), rule.type, rule.name, rule.node or 'None', remote_gateway_name)) req.remotes.append(gateway_msgs.RemoteRule(remote_gateway_name, rule)) resp = pull(req) if resp.result != 0: raise GatewaySampleRuntimeError("failed to pull %s [%s]" % (rule.name, resp.error_message))
def _send_flip_rules_request(self, name, cancel): rules = [] rule = gateway_msgs.Rule() rule.node = '' rule.type = gateway_msgs.ConnectionType.SUBSCRIBER # could resolve this better by looking up the service info rule.name = "/services/turtlesim/%s/cmd_vel" % name rules.append(copy.deepcopy(rule)) rule.type = gateway_msgs.ConnectionType.PUBLISHER rule.name = "/services/turtlesim/%s/pose" % name rules.append(copy.deepcopy(rule)) # send the request request = gateway_srvs.RemoteRequest() request.cancel = cancel remote_rule = gateway_msgs.RemoteRule() remote_rule.gateway = name for rule in rules: remote_rule.rule = rule request.remotes.append(copy.deepcopy(remote_rule)) try: self._gateway_flip_service(request) except rospy.ServiceException: # communication failed rospy.logerr("TurtleHerder : failed to send flip rules") return except rospy.ROSInterruptException: rospy.loginfo("TurtleHerder : shutdown while contacting the gateway flip service") return
def pull(gate, remote, local, topic, node): rospy.init_node('generic_puller') rospy.wait_for_service('/gateway/pull') remote_gateway = gate[0] pull_service = rospy.ServiceProxy('/gateway/pull', gateway_srvs.Remote) req = gateway_srvs.RemoteRequest() req.cancel = False req.remotes = [] rule = gateway_msgs.Rule() if topic[0][0] == '/': rule.name = topic[0] elif not remote: rule.name = '/' + topic[0] ; else: rule.name = '/' + remote[0] + '/' + topic[0] rule.type = gateway_msgs.ConnectionType.PUBLISHER if not node: rule.node = '' elif node[0][0] == '/': rule.node = node[0] elif not local: rule.node = '/' + node[0] else: rule.node = '/' + local[0] + '/' + node[0] req.remotes.append(gateway_msgs.RemoteRule(remote_gateway, rule)) rospy.loginfo("Pull : [%s,%s,%s,%s]."%(remote_gateway, rule.name, rule.type, rule.node)) resp = pull_service(req) if resp.result != 0: rospy.logerr("Pull : %s"%resp.error_message) rospy.loginfo("Finished pulling connection.")
def _pull_concert_client(self): ''' Pulls platform information from the advertised platform_info on another ros system. It is just a one-shot only used at construction time. It pulls platform_info and list_apps information. It also pulls the required handles in for further manipulation ('status' and 'invite') ''' rospy.loginfo("Conductor: retrieving client information [%s]" % self.name) pull_service = rospy.ServiceProxy('~pull', gateway_srvs.Remote) req = gateway_srvs.RemoteRequest() req.cancel = False req.remotes = [] for service_name in ['platform_info', 'list_apps', 'status', 'invite']: rule = gateway_msgs.Rule() rule.name = str('/' + self.gateway_name + '/' + service_name) rule.node = '' rule.type = gateway_msgs.ConnectionType.SERVICE req.remotes.append( gateway_msgs.RemoteRule(self.gateway_name.lstrip('/'), rule)) resp = pull_service(req) if resp.result != 0: rospy.logwarn( "Conductor: failed to pull the platform info service from the client." ) return None
def advertise_tutorials(cancel=False, regex_patterns=False, ns=_gateway_namespace): rospy.wait_for_service(ns + '/advertise') advertise = rospy.ServiceProxy(ns + '/advertise', gateway_srvs.Advertise) req = gateway_srvs.AdvertiseRequest() req.cancel = cancel rule = gateway_msgs.Rule() if regex_patterns: names, nodes = create_tutorial_dictionaries(use_regex_patterns=True) else: names, nodes = create_tutorial_dictionaries(use_regex_patterns=False) for connection_type in connection_types: req.rules = [] rule.name = names[connection_type] rule.type = connection_type rule.node = nodes[connection_type] rospy.loginfo("Advertise : %s [%s,%s,%s]." % (_action_text( cancel, 'advertising'), rule.type, rule.name, rule.node or 'None')) req.rules.append(rule) resp = advertise(req) if resp.result == gateway_msgs.ErrorCodes.ADVERTISEMENT_EXISTS: # already advertising all error is ignored. this call only has no effect. pass elif resp.result != 0: raise GatewaySampleRuntimeError("failed to advertise %s [%s]" % (rule.name, resp.error_message))
def flip_tutorials(remote_gateway_name=None, cancel=False, regex_patterns=False, ns=_gateway_namespace): rospy.wait_for_service(ns + '/flip') flip = rospy.ServiceProxy(ns + '/flip', gateway_srvs.Remote) if not remote_gateway_name: remote_gateway_name = find_first_remote_gateway() req = gateway_srvs.RemoteRequest() req.cancel = cancel if regex_patterns: names, nodes = create_tutorial_dictionaries(use_regex_patterns=True) else: names, nodes = create_tutorial_dictionaries(use_regex_patterns=False) req.remotes = [] for connection_type in connection_types: rule = gateway_msgs.Rule() rule.name = names[connection_type] rule.type = connection_type rule.node = nodes[connection_type] rospy.loginfo( "Flip : %s [%s,%s,%s][%s]." % (_action_text(cancel, 'requesting flip to gateway'), rule.type, rule.name, rule.node or 'None', remote_gateway_name)) req.remotes.append(gateway_msgs.RemoteRule(remote_gateway_name, rule)) resp = flip(req) if resp.result == gateway_msgs.ErrorCodes.FLIP_RULE_ALREADY_EXISTS: # already flipped all error is ignored. this call only has no effect. pass elif resp.result != 0: raise GatewaySampleRuntimeError("failed to flip %s [%s]" % (rule.name, resp.error_message))
def advertise(namespace, topic, node): rospy.init_node('generic_advertiser') rospy.wait_for_service('/gateway/advertise') advertise_service = rospy.ServiceProxy('/gateway/advertise', gateway_srvs.Advertise) req = gateway_srvs.AdvertiseRequest() rule = gateway_msgs.Rule() if topic[0][0] == '/': rule.name = topic[0] elif not namespace: rule.name = '/' + topic[0] else: rule.name = '/' + namespace[0] + '/' + topic[0] rule.type = gateway_msgs.ConnectionType.PUBLISHER if not node: rule.node = '' elif node[0][0] == '/': rule.node = node[0] elif not namespace: rule.node = '/' + node[0] else: rule.node = '/' + namespace[0] + '/' + node[0] req.rules.append(rule) rospy.loginfo("Advertise : [%s,%s,%s]." % (rule.name, rule.type, rule.node)) resp = advertise_service(req) if resp.result != 0: rospy.logerr("Advertise : %s" % resp.error_message) rospy.loginfo("Finished advertising connection.")
def flip(gate, remote, local, topic, node): rospy.init_node('generic_flip_subscriber') remote_gateway = gate[0] flip_service = rospy.ServiceProxy('/gateway/flip', gateway_srvs.Remote) req = gateway_srvs.RemoteRequest() req.cancel = False req.remotes = [] rule = gateway_msgs.Rule() if topic[0][0] == '/': rule.name = topic[0] elif not remote: rule.name = '/' + topic[0] else: rule.name = '/' + remote[0] + '/' + topic[0] rule.type = gateway_msgs.ConnectionType.SUBSCRIBER if not node: rule.node = '' elif node[0][0] == '/': rule.node = node[0] elif not local: rule.node = '/' + node[0] else: rule.node = '/' + local[0] + '/' + node[0] req.remotes.append(gateway_msgs.RemoteRule(remote_gateway, rule)) rospy.loginfo("Flip : [%s,%s,%s,%s]." % (remote_gateway, rule.name, rule.type, rule.node)) resp = flip_service(req) if resp.result != 0: rospy.logerr("Flip : %s" % resp.error_message) rospy.loginfo("Finished flipping connection.")
def _get_connections_from_pub_sub_chan_dict(ccproxy_channel_dict, connection_type): connections = set() for name, topic in ccproxy_channel_dict.iteritems(): topic_name = topic.name topic_type = topic.type nodes = topic.nodes for node in nodes: connection = Connection(gateway_msgs.Rule(connection_type, topic_name, node[0]), topic_type, topic_type, node[1]) connections.add(connection) return connections
def _get_connections_from_action_chan_dict(ccproxy_channel_dict, connection_type): connections = set() for name, action in ccproxy_channel_dict.iteritems(): action_name = action.name goal_topic_type = action.type nodes = action.nodes for node in nodes: connection = Connection(gateway_msgs.Rule(connection_type, action_name, node[0]), goal_topic_type, goal_topic_type, node[1]) # node_uri connections.add(connection) return connections
def _get_connections_from_service_chan_dict(ccproxy_channel_dict, connection_type): connections = set() for name, service in ccproxy_channel_dict.iteritems(): service_name = service.name service_type = service.type service_uri = service.xmlrpc_uri nodes = service.nodes for node in nodes: connection = Connection(gateway_msgs.Rule(connection_type, service_name, node[0]), service_type, service_uri, node[1]) connections.add(connection) return connections
def request_pulls(self, remote_gateway_name, cancel=False, service_names=['platform_info', 'list_rapps', 'invite'], topic_names=['status']): """ Handles pull requests and cancels from request gateways for the conductor. Note this only applies to topics/services relevant for interacting with concert clients. :param str remote_gateway_name: name of a remote gateway to apply to all rules :param bool cancel: to register or unregister the pull requests """ req = gateway_srvs.RemoteRequest() req.cancel = cancel req.remotes = [] for service_name in service_names: rule = gateway_msgs.Rule() rule.name = str('/' + remote_gateway_name.lower().replace(' ', '_') + '/' + service_name) rule.node = '' rule.type = gateway_msgs.ConnectionType.SERVICE req.remotes.append( gateway_msgs.RemoteRule(remote_gateway_name.lstrip('/'), rule)) for publisher_name in topic_names: rule = gateway_msgs.Rule() rule.name = str('/' + remote_gateway_name.lower().replace(' ', '_') + '/' + publisher_name) rule.node = '' rule.type = gateway_msgs.ConnectionType.PUBLISHER req.remotes.append( gateway_msgs.RemoteRule(remote_gateway_name.lstrip('/'), rule)) # TODO : exception handling for this call response = self._services['pull'](req) if response.result != gateway_msgs.ErrorCodes.SUCCESS and not cancel: # don't worry about errors on cleanup rospy.logwarn( "Conductor: failed to register pull requests from the concert client [%s]%s" % (remote_gateway_name, service_names) ) # TODO : exceptions, but what kind of failures?
def create_gateway_rule(name, connection_type, node_name=''): ''' Quickly hack a gateway rule. @param name : connection name (e.g. /chatter) @type string @param connection_type : one of pub, sub, etc. @type gateway_msgs.ConnectionType,XXX constants ''' r = gateway_msgs.Rule() r.name = name r.type = connection_type r.node = node_name return r
def pull(self, type): rule = gateway_msgs.Rule() rule.name = self.names[type] rule.type = type rule.node = self.nodes[type] self.req.remotes.append(gateway_msgs.RemoteRule(self.gateway, rule)) resp = self.pull_service(self.req) if resp.result == gateway_msgs.ErrorCodes.SUCCESS: rospy.loginfo("Pull : %s [%s,%s,%s,%s]." % (self.action_text, self.gateway, rule.type, rule.name, rule.node or 'None')) else: rospy.logerr("Pull : pull failed [%s]" % str(resp.error_message)) self.req.remotes = []
def _flip_rules(self): rules = [] rule = gateway_msgs.Rule() rule.node = rospy.get_name() rule.type = gateway_msgs.ConnectionType.PUBLISHER rule.name = rospy.resolve_name("spawn/request") rules.append(copy.deepcopy(rule)) rule.name = rospy.resolve_name("kill/request") rules.append(copy.deepcopy(rule)) rule.type = gateway_msgs.ConnectionType.SUBSCRIBER rule.name = rospy.resolve_name("spawn/response") rules.append(copy.deepcopy(rule)) rule.name = rospy.resolve_name("kill/response") rules.append(copy.deepcopy(rule)) return rules
def cancel_pulls(self): ''' Cancel any pulls for a client which failed to construct (e.g. in the init() when the service calls fail. ''' pull_service = rospy.ServiceProxy('~pull', gateway_srvs.Remote) req = gateway_srvs.RemoteRequest() req.cancel = True req.remotes = [] for service_name in ['platform_info', 'list_apps', 'status', 'invite']: rule = gateway_msgs.Rule() rule.name = str('/' + self.gateway_name + '/' + service_name) rule.node = '' rule.type = gateway_msgs.ConnectionType.SERVICE req.remotes.append( gateway_msgs.RemoteRule(self.gateway_name.lstrip('/'), rule)) unused_resp = pull_service(req)
def advertise(topic): rospy.init_node('advertise_hub_publisher') rospy.wait_for_service('/gateway/advertise') advertise_service=rospy.ServiceProxy('/gateway/advertise', gateway_srvs.Advertise) req = gateway_srvs.AdvertiseRequest() rule = gateway_msgs.Rule() rule.name = '/' + topic rule.type = gateway_msgs.ConnectionType.PUBLISHER rule.node = "" req.rules.append(rule) rospy.loginfo("Advertise : [%s,%s,%s]."%(rule.name, rule.type, rule.node)) resp = advertise_service(req) if resp.result != 0: rospy.logerr("Advertise : %s"%resp.error_message) rospy.loginfo("Finished advertising connection.")
def flip(namespace, topic, node): rospy.init_node('flip_remote_publisher') remote_gateway = "Hub_Gateway" flip_service = rospy.ServiceProxy('/gateway/flip', gateway_srvs.Remote) req = gateway_srvs.RemoteRequest() req.cancel = False req.remotes = [] rule = gateway_msgs.Rule() rule.name = '/' + namespace + '/' + topic rule.type = gateway_msgs.ConnectionType.PUBLISHER rule.node = '/' + namespace + '/' + node req.remotes.append(gateway_msgs.RemoteRule(remote_gateway, rule)) rospy.loginfo("Flip : [%s,%s,%s,%s]." % (remote_gateway, rule.name, rule.type, rule.node)) resp = flip_service(req) if resp.result != 0: rospy.logerr("Flip : %s" % resp.error_message) rospy.loginfo("Finished flipping connection.")
def pull(topic): rospy.init_node('pull_hub_publisher') rospy.wait_for_service('/gateway/pull') remote_gateway = "Hub_Gateway" pull_service = rospy.ServiceProxy('/gateway/pull', gateway_srvs.Remote) req = gateway_srvs.RemoteRequest() req.cancel = False req.remotes = [] rule = gateway_msgs.Rule() rule.name = '/' + topic rule.type = gateway_msgs.ConnectionType.PUBLISHER rule.node = "" req.remotes.append(gateway_msgs.RemoteRule(remote_gateway, rule)) rospy.loginfo("Pull : [%s,%s,%s,%s]." % (remote_gateway, rule.name, rule.type, rule.node)) resp = pull_service(req) if resp.result != 0: rospy.logerr("Pull : %s" % resp.error_message) rospy.loginfo("Finished pulling connection.")
def flip(namespace, topic, node, gate): rospy.init_node('flip_hub_subscriber') remote_gateway = gate + '_gateway' flip_service = rospy.ServiceProxy('/gateway/flip', gateway_srvs.Remote) req = gateway_srvs.RemoteRequest() req.cancel = False req.remotes = [] rule = gateway_msgs.Rule() if topic[0] == '/': rule.name = topic else: rule.name = '/' + namespace + '/' + topic rule.type = gateway_msgs.ConnectionType.SUBSCRIBER rule.node = '/' + node req.remotes.append(gateway_msgs.RemoteRule(remote_gateway, rule)) rospy.loginfo("Flip : [%s,%s,%s,%s]." % (remote_gateway, rule.name, rule.type, rule.node)) resp = flip_service(req) if resp.result != 0: rospy.logerr("Flip : %s" % resp.error_message) rospy.loginfo("Finished flipping connection.")
def remote_gateway_info(self, gateway): ''' Return remote gateway information for the specified gateway string id. @param gateways : gateway id string to search for @type string @return remote gateway information @rtype gateway_msgs.RemotGateway or None ''' firewall = self._redis_server.get(hub_api.create_rocon_gateway_key(gateway, 'firewall')) if firewall is None: return None # equivalent to saying no gateway of this id found ip = self._redis_server.get(hub_api.create_rocon_gateway_key(gateway, 'ip')) if ip is None: return None # hub information not available/correct remote_gateway = gateway_msgs.RemoteGateway() remote_gateway.name = gateway remote_gateway.ip = ip remote_gateway.firewall = True if int(firewall) else False remote_gateway.public_interface = [] encoded_advertisements = self._redis_server.smembers( hub_api.create_rocon_gateway_key(gateway, 'advertisements')) for encoded_advertisement in encoded_advertisements: advertisement = utils.deserialize_connection(encoded_advertisement) remote_gateway.public_interface.append(advertisement.rule) remote_gateway.flipped_interface = [] encoded_flips = self._redis_server.smembers(hub_api.create_rocon_gateway_key(gateway, 'flips')) for encoded_flip in encoded_flips: [target_gateway, name, connection_type, node] = utils.deserialize(encoded_flip) remote_rule = gateway_msgs.RemoteRule(target_gateway, gateway_msgs.Rule(connection_type, name, node)) remote_gateway.flipped_interface.append(remote_rule) remote_gateway.pulled_interface = [] encoded_pulls = self._redis_server.smembers(hub_api.create_rocon_gateway_key(gateway, 'pulls')) for encoded_pull in encoded_pulls: [target_gateway, name, connection_type, node] = utils.deserialize(encoded_pull) remote_rule = gateway_msgs.RemoteRule(target_gateway, gateway_msgs.Rule(connection_type, name, node)) remote_gateway.pulled_interface.append(remote_rule) # Gateway health/network connection statistics indicators gateway_available_key = hub_api.create_rocon_gateway_key(gateway, 'available') remote_gateway.conn_stats.gateway_available = \ self._parse_redis_bool(self._redis_server.get(gateway_available_key)) time_since_last_seen_key = hub_api.create_rocon_gateway_key(gateway, 'time_since_last_seen') remote_gateway.conn_stats.time_since_last_seen = \ self._parse_redis_int(self._redis_server.get(time_since_last_seen_key)) ping_latency_min_key = hub_api.create_rocon_gateway_key(gateway, 'latency:min') remote_gateway.conn_stats.ping_latency_min = \ self._parse_redis_float(self._redis_server.get(ping_latency_min_key)) ping_latency_max_key = hub_api.create_rocon_gateway_key(gateway, 'latency:max') remote_gateway.conn_stats.ping_latency_max = \ self._parse_redis_float(self._redis_server.get(ping_latency_max_key)) ping_latency_avg_key = hub_api.create_rocon_gateway_key(gateway, 'latency:avg') remote_gateway.conn_stats.ping_latency_avg = \ self._parse_redis_float(self._redis_server.get(ping_latency_avg_key)) ping_latency_mdev_key = hub_api.create_rocon_gateway_key(gateway, 'latency:mdev') remote_gateway.conn_stats.ping_latency_mdev = \ self._parse_redis_float(self._redis_server.get(ping_latency_mdev_key)) # Gateway network connection indicators network_info_available_key = hub_api.create_rocon_gateway_key(gateway, 'network:info_available') remote_gateway.conn_stats.network_info_available = \ self._parse_redis_bool(self._redis_server.get(network_info_available_key)) if not remote_gateway.conn_stats.network_info_available: return remote_gateway network_type_key = hub_api.create_rocon_gateway_key(gateway, 'network:type') remote_gateway.conn_stats.network_type = \ self._parse_redis_int(self._redis_server.get(network_type_key)) if remote_gateway.conn_stats.network_type == gateway_msgs.RemoteGateway.WIRED: return remote_gateway wireless_bitrate_key = hub_api.create_rocon_gateway_key(gateway, 'wireless:bitrate') remote_gateway.conn_stats.wireless_bitrate = \ self._parse_redis_float(self._redis_server.get(wireless_bitrate_key)) wireless_link_quality_key = hub_api.create_rocon_gateway_key(gateway, 'wireless:quality') remote_gateway.conn_stats.wireless_link_quality = \ self._parse_redis_int(self._redis_server.get(wireless_link_quality_key)) wireless_signal_level_key = hub_api.create_rocon_gateway_key(gateway, 'wireless:signal_level') remote_gateway.conn_stats.wireless_signal_level = \ self._parse_redis_float(self._redis_server.get(wireless_signal_level_key)) wireless_noise_level_key = hub_api.create_rocon_gateway_key(gateway, 'wireless:noise_level') remote_gateway.conn_stats.wireless_noise_level = \ self._parse_redis_float(self._redis_server.get(wireless_noise_level_key)) return remote_gateway
def get_rule_from_list(rule_argument_list): return gateway_msgs.Rule(rule_argument_list[0], rule_argument_list[1], rule_argument_list[2])
def get_connection_from_list(connection_argument_list): rule = gateway_msgs.Rule(connection_argument_list[0], connection_argument_list[1], connection_argument_list[2]) return Connection(rule, connection_argument_list[3], connection_argument_list[4], connection_argument_list[5])
def generate_connection_details(self, connection_type, name, node): """ Creates all the extra details to create a connection object from a rule. @param connection_type : the connection type (one of gateway_msgs.msg.ConnectionType) @type string @param name : the name of the connection @type string @param node : the master node name it comes from @param string @return the utils.Connection object complete with type_info and xmlrpc_uri @type utils.Connection """ # Very important here to check for the results of xmlrpc_uri and especially topic_type # https://github.com/robotics-in-concert/rocon_multimaster/issues/173 # In the watcher thread, we get the local connection index (whereby the arguments of this function # come from) via master.get_connection_state. That means there is a small amount of time from # getting the topic name, to checking for hte xmlrpc_uri and especially topic_type here in which # the topic could have disappeared. When this happens, it returns None. connections = [] xmlrpc_uri = node.split(",")[1] node = node.split(",")[0] if xmlrpc_uri is None: return connections if connection_type == rocon_python_comms.PUBLISHER or connection_type == rocon_python_comms.SUBSCRIBER: type_info = rostopic.get_topic_type(name)[0] # message type if type_info is not None: connections.append( utils.Connection( gateway_msgs.Rule(connection_type, name, node), type_info, type_info, xmlrpc_uri)) else: rospy.logwarn( 'Gateway : [%s] does not have type_info. Cannot flip' % name) elif connection_type == rocon_python_comms.SERVICE: type_info = rosservice.get_service_uri(name) type_msg = rosservice.get_service_type(name) if type_info is not None: connections.append( utils.Connection( gateway_msgs.Rule(connection_type, name, node), type_msg, type_info, xmlrpc_uri)) elif connection_type == rocon_python_comms.ACTION_SERVER: goal_type_info = rostopic.get_topic_type(name + '/goal')[ 0] # message type cancel_type_info = rostopic.get_topic_type(name + '/cancel')[ 0] # message type status_type_info = rostopic.get_topic_type(name + '/status')[ 0] # message type feedback_type_info = rostopic.get_topic_type(name + '/feedback')[ 0] # message type result_type_info = rostopic.get_topic_type(name + '/result')[ 0] # message type if (goal_type_info is not None and cancel_type_info is not None and status_type_info is not None and feedback_type_info is not None and result_type_info is not None): connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/goal', node), goal_type_info, goal_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/cancel', node), cancel_type_info, cancel_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/status', node), status_type_info, status_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/feedback', node), feedback_type_info, feedback_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/result', node), result_type_info, result_type_info, xmlrpc_uri)) elif connection_type == rocon_python_comms.ACTION_CLIENT: goal_type_info = rostopic.get_topic_type(name + '/goal')[ 0] # message type cancel_type_info = rostopic.get_topic_type(name + '/cancel')[ 0] # message type status_type_info = rostopic.get_topic_type(name + '/status')[ 0] # message type feedback_type_info = rostopic.get_topic_type(name + '/feedback')[ 0] # message type result_type_info = rostopic.get_topic_type(name + '/result')[ 0] # message type if (goal_type_info is not None and cancel_type_info is not None and status_type_info is not None and feedback_type_info is not None and result_type_info is not None): connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/goal', node), goal_type_info, goal_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.PUBLISHER, name + '/cancel', node), cancel_type_info, cancel_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/status', node), status_type_info, status_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/feedback', node), feedback_type_info, feedback_type_info, xmlrpc_uri)) connections.append( utils.Connection( gateway_msgs.Rule(rocon_python_comms.SUBSCRIBER, name + '/result', node), result_type_info, result_type_info, xmlrpc_uri)) return connections