Пример #1
0
    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 == PUBLISHER or connection_type == SUBSCRIBER:
            type_info = rostopic.get_topic_type(name)[0]  # message type
            if type_info is not None:
                connection = utils.Connection(
                    Rule(connection_type, name, node), type_info, xmlrpc_uri)
        elif connection_type == SERVICE:
            type_info = rosservice.get_service_uri(name)
            if type_info is not None:
                connection = utils.Connection(
                    Rule(connection_type, name, node), type_info, xmlrpc_uri)
        elif connection_type == ACTION_SERVER or connection_type == 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(
                    Rule(connection_type, name, node), type_info, xmlrpc_uri)
        return connection
Пример #2
0
def deserialize_connection(connection_str):
    deserialized_list = deserialize(connection_str)
    rule = Rule(deserialized_list[0],
                deserialized_list[1],
                deserialized_list[2]
                )
    return Connection(rule, deserialized_list[3], deserialized_list[4])
Пример #3
0
def generate_remote_rules(param):
    '''
       Converts a param of the suitable type (default_flips, default_pulls) into
       a list of RemoteRule objects and a list of target gateways for flip_all/pull_all.

       @param yaml object
       @type complicated

       @return list of remote rules
       @return RemoteRule[]
    '''
    remote_rules = []
    all_targets = []
    pattern = re.compile("None", re.IGNORECASE)
    for remote_rule in param:
        if 'rule' in remote_rule:
            # maybe also check for '' here?
            node = None if pattern.match(
                remote_rule['rule']['node']) else remote_rule['rule']['node']
            remote_rules.append(
                RemoteRule(
                    remote_rule['gateway'],
                    Rule(remote_rule['rule']['type'],
                         remote_rule['rule']['name'], node)))
        else:
            all_targets.append(remote_rule['gateway'])
    return remote_rules, all_targets
Пример #4
0
def generate_rules(param):
    '''
      Converts a param of the suitable type (see default_blacklist.yaml)
      into a dictionary of Rule types.

      @return all rules as gateway_msgs.msg.Rule objects in our usual keyed dictionary format
      @rtype type keyed dictionary of Rule lists
    '''
    rules = utils.create_empty_connection_type_dictionary()
    for value in param:
        rule = Rule()
        rule.name = value['name']
        # maybe also check for '' here?
        pattern = re.compile("None", re.IGNORECASE)
        if pattern.match(value['node']):
            rule.node = ''  # ROS Message fields should not be None, maybe not a problem here though, see below
        else:
            rule.node = value['node']
        rule.type = value['type']
        rules[rule.type].append(rule)
    return rules
    def _generatePublic(self, rule):
        '''
          Given a rule, determines if the rule is allowed. If it is
          allowed, then returns the corresponding Rule object

          @param rules : the given rules to match
          @type Rule
          @return The generated Rule if allowed, None if no match
          @rtype Rule || None
        '''
        if self._allowRule(rule):
            return Rule(rule)
        return None
    def advertise_all(self, blacklist):
        '''
          Allow all rules apart from the ones in the provided blacklist +
          default blacklist

          @param blacklist : list of Rule objects
          @type list : list of Rule objects

          @return failure if already advertising all, success otherwise
          @rtype bool
        '''
        rospy.loginfo("Gateway : received a request advertise everything!")
        self.lock.acquire()

        # Check if advertise all already enabled
        if self.advertise_all_enabled:
            self.lock.release()
            return False
        self.advertise_all_enabled = True

        # generate watchlist
        self.watchlist = utils.create_empty_connection_type_dictionary(
        )  # easy hack for getting a clean watchlist
        for connection_type in utils.connection_types:
            allow_all_rule = Rule()
            allow_all_rule.name = '.*'
            allow_all_rule.type = connection_type
            allow_all_rule.node = '.*'
            self.watchlist[connection_type].append(allow_all_rule)

        # generate blacklist (while making sure only unique rules get added)
        self.blacklist = copy.deepcopy(self._default_blacklist)
        for rule in blacklist:
            if not publicRuleExists(rule, self.blacklist[rule.type]):
                self.blacklist[rule.type].append(rule)

        self.lock.release()
        return True
Пример #7
0
    def advertise_all(self, blacklist):
        '''
          Allow all rules apart from the ones in the provided blacklist +
          default blacklist

          @param blacklist : list of Rule objects
          @type list : list of Rule objects

          @return failure if already advertising all, success otherwise
          @rtype bool
        '''
        rospy.loginfo("Gateway : received a request advertise everything!")
        self.lock.acquire()

        # Check if advertise all already enabled
        if self.advertise_all_enabled:
            self.lock.release()
            return False
        self.advertise_all_enabled = True

        # generate watchlist
        self.watchlist = utils.create_empty_connection_type_dictionary()  # easy hack for getting a clean watchlist
        for connection_type in utils.connection_types:
            allow_all_rule = Rule()
            allow_all_rule.name = '.*'
            allow_all_rule.type = connection_type
            allow_all_rule.node = '.*'
            self.watchlist[connection_type].append(allow_all_rule)

        # generate blacklist (while making sure only unique rules get added)
        self.blacklist = copy.deepcopy(self._default_blacklist)
        for rule in blacklist:
            if not publicRuleExists(rule, self.blacklist[rule.type]):
                self.blacklist[rule.type].append(rule)

        self.lock.release()
        return True
Пример #8
0
    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
        '''
        xmlrpc_uri = self.lookupNode(node)
        if connection_type == PUBLISHER or connection_type == SUBSCRIBER:
            type_info = rostopic.get_topic_type(name)[0]  # message type
            connection = utils.Connection(Rule(connection_type, name, node),
                                          type_info, xmlrpc_uri)
        elif connection_type == SERVICE:
            type_info = rosservice.get_service_uri(name)
            connection = utils.Connection(Rule(connection_type, name, node),
                                          type_info, xmlrpc_uri)
        elif connection_type == ACTION_SERVER or connection_type == 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
            connection = utils.Connection(Rule(connection_type, name, node),
                                          type_info, xmlrpc_uri)
        return connection
Пример #9
0
    def get_flip_rule_list(self, name):
        """
        Returns flip rules of given robot type
        """
        rules = []

        flip = {}
        flip['pub'] = ConnectionType.PUBLISHER
        flip['sub'] = ConnectionType.SUBSCRIBER
        flip['srv'] = ConnectionType.SERVICE

        for key, typ in flip.items():
            if key in self._flip_rules:
                for topic in self._flip_rules[key]:
                    if topic.startswith('/'):
                        r = Rule(typ, topic, None)
                    else:
                        r = Rule(typ, name + '/' + topic, None)
                    rules.append(r)

        # flips tf and clock by default
        rules.append(Rule(ConnectionType.PUBLISHER, '/clock', None))
        rules.append(Rule(ConnectionType.PUBLISHER, '/tf', None))
        return rules
Пример #10
0
 def _get_connections_from_service_list(self, connection_list,
                                        connection_type):
     connections = []
     for service in connection_list:
         service_name = service[0]
         #service_uri = rosservice.get_service_uri(service_name)
         nodes = service[1]
         for node in nodes:
             #try:
             #    node_uri = self.lookupNode(node)
             #except:
             #    continue
             rule = Rule(connection_type, service_name, node)
             connection = utils.Connection(rule, None,
                                           None)  # service_uri, node_uri
             connections.append(connection)
     return connections
Пример #11
0
 def _get_connections_from_pub_sub_list(self, connection_list,
                                        connection_type):
     connections = []
     for topic in connection_list:
         topic_name = topic[0]
         #topic_type = rostopic.get_topic_type(topic_name)
         #topic_type = topic_type[0]
         nodes = topic[1]
         for node in nodes:
             #try:
             #node_uri = self.lookupNode(node)
             #except:
             #    continue
             rule = Rule(connection_type, topic_name, node)
             connection = utils.Connection(rule, None,
                                           None)  # topic_type, node_uri
             connections.append(connection)
     return connections
Пример #12
0
 def _get_connections_from_action_list(self, connection_list,
                                       connection_type):
     connections = []
     for action in connection_list:
         action_name = action[0]
         #goal_topic = action_name + '/goal'
         #goal_topic_type = rostopic.get_topic_type(goal_topic)
         #topic_type = re.sub('ActionGoal$', '', goal_topic_type[0])  # Base type for action
         nodes = action[1]
         for node in nodes:
             #try:
             #    node_uri = self.lookupNode(node)
             #except:
             #    continue
             rule = Rule(connection_type, action_name, node)
             connection = utils.Connection(rule, None,
                                           None)  # topic_type, node_uri
             connections.append(connection)
     return connections
Пример #13
0
def generate_rules(param):
    '''
      Converts a param of the suitable type (see default_blacklist.yaml)
      into a dictionary of Rule types.

      @return all rules as gateway_msgs.msg.Rule objects in our usual keyed dictionary format
      @rtype type keyed dictionary of Rule lists
    '''
    rules = utils.create_empty_connection_type_dictionary()
    for value in param:
        rule = Rule()
        rule.name = value['name']
        # maybe also check for '' here?
        pattern = re.compile("None", re.IGNORECASE)
        if pattern.match(value['node']):
            rule.node = ''  # ROS Message fields should not be None, maybe not a problem here though, see below
        else:
            rule.node = value['node']
        rule.type = value['type']
        rules[rule.type].append(rule)
    return rules
Пример #14
0
    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 = self.lookupNode(node)
        if xmlrpc_uri is None:
            return connections
        if connection_type == PUBLISHER or connection_type == SUBSCRIBER:
            type_info = rostopic.get_topic_type(name)[0]  # message type
            if type_info is not None:
                connections.append(
                    utils.Connection(Rule(connection_type, name, node),
                                     type_info, xmlrpc_uri))
        elif connection_type == SERVICE:
            type_info = rosservice.get_service_uri(name)
            if type_info is not None:
                connections.append(
                    utils.Connection(Rule(connection_type, name, node),
                                     type_info, xmlrpc_uri))
        elif connection_type == 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(Rule(SUBSCRIBER, name + '/goal', node),
                                     goal_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(Rule(SUBSCRIBER, name + '/cancel', node),
                                     cancel_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(Rule(PUBLISHER, name + '/status', node),
                                     status_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(Rule(PUBLISHER, name + '/feedback', node),
                                     feedback_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(Rule(PUBLISHER, name + '/result', node),
                                     result_type_info, xmlrpc_uri))
        elif connection_type == 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(Rule(PUBLISHER, name + '/goal', node),
                                     goal_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(Rule(PUBLISHER, name + '/cancel', node),
                                     cancel_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(Rule(SUBSCRIBER, name + '/status', node),
                                     status_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(
                        Rule(SUBSCRIBER, name + '/feedback', node),
                        feedback_type_info, xmlrpc_uri))
                connections.append(
                    utils.Connection(Rule(SUBSCRIBER, name + '/result', node),
                                     result_type_info, xmlrpc_uri))
        return connections
Пример #15
0
def get_rule_from_list(rule_argument_list):
    return Rule(rule_argument_list[0], rule_argument_list[1], rule_argument_list[2])
Пример #16
0
def get_connection_from_list(connection_argument_list):
    rule = Rule(connection_argument_list[0], connection_argument_list[1], connection_argument_list[2])
    return Connection(rule, connection_argument_list[3], connection_argument_list[4])
Пример #17
0
    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
        '''
        xmlrpc_uri = self.lookupNode(node)
        connections = []
        if connection_type == PUBLISHER or connection_type == SUBSCRIBER:
            type_info = rostopic.get_topic_type(name)[0]  # message type
            connections.append(
                utils.Connection(Rule(connection_type, name, node), type_info,
                                 xmlrpc_uri))
        elif connection_type == SERVICE:
            type_info = rosservice.get_service_uri(name)
            connections.append(
                utils.Connection(Rule(connection_type, name, node), type_info,
                                 xmlrpc_uri))
        elif connection_type == ACTION_SERVER:
            type_info = rostopic.get_topic_type(name +
                                                '/goal')[0]  # message type
            connections.append(
                utils.Connection(Rule(SUBSCRIBER, name + '/goal', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/cancel')[0]  # message type
            connections.append(
                utils.Connection(Rule(SUBSCRIBER, name + '/cancel', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/status')[0]  # message type
            connections.append(
                utils.Connection(Rule(PUBLISHER, name + '/status', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/feedback')[0]  # message type
            connections.append(
                utils.Connection(Rule(PUBLISHER, name + '/feedback', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/result')[0]  # message type
            connections.append(
                utils.Connection(Rule(PUBLISHER, name + '/result', node),
                                 type_info, xmlrpc_uri))
        elif connection_type == ACTION_CLIENT:
            type_info = rostopic.get_topic_type(name +
                                                '/goal')[0]  # message type
            connections.append(
                utils.Connection(Rule(PUBLISHER, name + '/goal', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/cancel')[0]  # message type
            connections.append(
                utils.Connection(Rule(PUBLISHER, name + '/cancel', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/status')[0]  # message type
            connections.append(
                utils.Connection(Rule(SUBSCRIBER, name + '/status', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/feedback')[0]  # message type
            connections.append(
                utils.Connection(Rule(SUBSCRIBER, name + '/feedback', node),
                                 type_info, xmlrpc_uri))
            type_info = rostopic.get_topic_type(name +
                                                '/result')[0]  # message type
            connections.append(
                utils.Connection(Rule(SUBSCRIBER, name + '/result', node),
                                 type_info, xmlrpc_uri))
        return connections