public_interface.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #       
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_multimaster/master/rocon_gateway/LICENSE 
00005 #
00006 
00007 ##############################################################################
00008 # Imports
00009 ##############################################################################
00010 
00011 import copy
00012 import re
00013 import threading
00014 
00015 import rospy
00016 
00017 # local imports
00018 import utils
00019 from gateway_msgs.msg import Rule
00020 
00021 ##############################################################################
00022 # Functions
00023 ##############################################################################
00024 
00025 def publicRuleExists(public_rule, public_rules):
00026     '''
00027       Checks that the public rule doesn't already exist in the list of public
00028       rules (which can represent the public interface or the rules themselves).
00029       We only need to compare the name/node as they uniquely identify the 
00030       name/regex
00031       
00032       @param public_rule : the rule to search for
00033       @type Rule
00034       
00035       @param public_rules : list of Rule (public, watchlist or blacklist)
00036       @type list : list of Rule objects
00037       
00038       @return True if the public rule exists, False otherwise
00039       @rtype bool
00040     '''
00041     for rule in public_rules:
00042         if rule.name == public_rule.name and \
00043            rule.node == public_rule.node:
00044             return True
00045     return False
00046 
00047 ##############################################################################
00048 # Public Interface
00049 ##############################################################################
00050 
00051 class PublicInterface(object):
00052     '''
00053       The public interface is the set of rules 
00054       (pubs/subs/services/actions) that are exposed and made available for 
00055       freely sharing with a multimaster system.
00056       
00057       It consists of: 
00058        * list of currently available rules to be shared 
00059        * list of rules and filters that will be watched 
00060          and shared if they become available 
00061       
00062     '''
00063     def __init__(self, default_rule_blacklist, default_rules):
00064         '''
00065           Initialises the public interface
00066 
00067           @param default_rule_blacklist : connection type keyed dictionary of rules
00068           @type str keyed dictionary of gateway_msgs.msg.Rule[] 
00069           
00070           @param default_rules : connection type keyed dictionary of rules
00071           @type str keyed dictionary of gateway_msgs.msg.Rule[] 
00072         '''
00073         # List of rules to be monitored and (un)advertised  as they 
00074         # become (un)available
00075         self.watchlist = utils.createEmptyConnectionTypeDictionary()
00076 
00077         # Default rules that cannot be advertised - used in AdvertiseAll mode
00078         self._default_blacklist = default_rule_blacklist
00079 
00080         # Default + custom blacklist - used in AdvertiseAll mode
00081         self.blacklist = self._default_blacklist
00082 
00083         # list of fully qualified connections currently being advertised
00084         self.public = utils.createEmptyConnectionTypeDictionary()
00085 
00086         self.advertise_all_enabled = False
00087 
00088         self.lock = threading.Lock()
00089         
00090         # Load up static rules.
00091         for connection_type in utils.connection_types:
00092             for rule in default_rules[connection_type]:
00093                 print rule
00094                 self.add_rule(rule)
00095 
00096     ##########################################################################
00097     # Public Interfaces
00098     ##########################################################################
00099 
00100     def add_rule(self, rule):
00101         '''
00102         Watch for a new public rule, as described for by the incoming message.
00103         
00104         @param rule : a rule msg from the advertise call
00105         @type Rule
00106 
00107         @return the rule if added, or None if the rule exists already
00108         @rtype Rule || None
00109         '''
00110         result = None
00111         self.lock.acquire()
00112         if not publicRuleExists(rule,self.watchlist[rule.type]):
00113             self.watchlist[rule.type].append(rule)
00114             result = rule
00115         self.lock.release()
00116         rospy.loginfo("Gateway : (req) advertise %s"%utils.formatRule(rule))
00117         return result
00118 
00119     def remove_rule(self, rule): 
00120         ''' 
00121         Attempt to remove a watchlist rule from the public interface. Be a
00122         bit careful looking for a rule to remove, depending on the node name,
00123         which can be set (exact rule/node name match) or None in which case all
00124         nodes of that kind of advertisement will match.
00125         
00126         @param rule : a rule to unadvertise
00127         @type Rule
00128 
00129         @return the list of rules removed
00130         @rtype Rule[]
00131         '''
00132 
00133         rospy.loginfo("Gateway : (req) unadvertise %s"%utils.formatRule(rule))
00134 
00135         if rule.node:
00136             # This looks for *exact* matches.
00137             try:
00138                 self.lock.acquire()
00139                 self.watchlist[rule.type].remove(rule)
00140                 self.lock.release()
00141                 return [rule]
00142             except ValueError:
00143                 self.lock.release()
00144                 return []
00145         else:
00146             # This looks for any flip rules which match except for the node name
00147             # also no need to check for type with the dic keys like they are
00148             existing_rules = []
00149             self.lock.acquire()
00150             for existing_rule in self.watchlist[rule.type]:
00151                 if (existing_rule.name == rule.name):
00152                     existing_rules.append(existing_rule)
00153             for rule in existing_rules:
00154                 self.watchlist[rule.type].remove(existing_rule) # not terribly optimal
00155             self.lock.release()
00156             return existing_rules
00157 
00158     def advertiseAll(self, blacklist):
00159         '''
00160           Allow all rules apart from the ones in the provided blacklist + 
00161           default blacklist
00162 
00163           @param blacklist : list of Rule objects
00164           @type list : list of Rule objects
00165 
00166           @return failure if already advertising all, success otherwise
00167           @rtype bool
00168         '''
00169         rospy.loginfo("Gateway : (req) advertise everything!")
00170         self.lock.acquire()
00171 
00172         # Check if advertise all already enabled 
00173         if self.advertise_all_enabled:
00174             self.lock.release()
00175             return False
00176         self.advertise_all_enabled = True
00177 
00178         # generate watchlist
00179         self.watchlist = utils.createEmptyConnectionTypeDictionary() #easy hack for getting a clean watchlist
00180         for connection_type in utils.connection_types:
00181             allow_all_rule = Rule()
00182             allow_all_rule.name = '.*'
00183             allow_all_rule.type = connection_type
00184             self.watchlist[connection_type].append(allow_all_rule)
00185 
00186         # generate blacklist (while making sure only unique rules get added)
00187         self.blacklist = copy.deepcopy(self._default_blacklist)
00188         for rule in blacklist:
00189             if not publicRuleExists(rule, self.blacklist[rule.type]):
00190                 self.blacklist[rule.type].append(rule)
00191 
00192         self.lock.release()
00193         return True
00194 
00195     def unadvertiseAll(self):
00196         '''
00197           Disallow the allow all mode, if enabled. If allow all mode is not
00198           enabled, remove everything from the public interface
00199         '''
00200         rospy.loginfo("Gateway : (req) remove all advertisements!")
00201         self.lock.acquire()
00202 
00203         # stop advertising all
00204         self.advertise_all_enabled = False
00205 
00206         # easy hack for resetting the watchlist and blacklist
00207         self.watchlist = utils.createEmptyConnectionTypeDictionary()
00208         self.blacklist = self._default_blacklist
00209 
00210         self.lock.release()
00211 
00212     ##########################################################################
00213     # List Accessors
00214     ##########################################################################
00215 
00216     def getInterface(self):
00217         list = []
00218         self.lock.acquire()
00219         for connection_type in utils.connection_types:
00220             list.extend([connection.rule for connection in self.public[connection_type]])
00221         self.lock.release()
00222         return list
00223 
00224     def getWatchlist(self):
00225         list = []
00226         self.lock.acquire()
00227         for connection_type in utils.connection_types:
00228             list.extend(self.watchlist[connection_type])
00229         self.lock.release()
00230         return list
00231 
00232     def getBlacklist(self):
00233         list = []
00234         self.lock.acquire()
00235         for connection_type in utils.connection_types:
00236             list.extend(self.blacklist[connection_type])
00237         self.lock.release()
00238         return list
00239 
00240     ##########################################################################
00241     # Filter
00242     ##########################################################################
00243 
00244     def _matchAgainstRuleList(self,rules,rule):
00245         '''
00246           Match a given rule/rule against a given rule list
00247 
00248           @param rules : the rules against which to match
00249           @type dict of list of Rule objects
00250           @param rule : the given rule/rule to match
00251           @type Rule
00252           @return the list of rules matched, None if no rules found
00253           @rtype list of Rules || None
00254         '''
00255         matched = False
00256         for r in rules[rule.type]:
00257             name_match_result = re.match(r.name, rule.name)
00258             if name_match_result and name_match_result.group() == rule.name:
00259                 if r.node:
00260                     node_match_result = re.match(r.node, rule.node)
00261                     if node_match_result and node_match_result.group() == rule.node:
00262                         matched = True
00263                 else:
00264                     matched = True
00265             if matched:
00266                 break
00267         return matched
00268 
00269     def _allowRule(self,rule):
00270         '''
00271           Determines whether a given rule should be allowed given the
00272           status of the current watchlist and blacklist
00273 
00274           @param rule : the given rule/rule to match
00275           @type Rule
00276           @return whether rule is allowed
00277           @rtype bool
00278         '''
00279         self.lock.acquire()
00280         matched_rules = self._matchAgainstRuleList(self.watchlist,rule)
00281         matched_blacklisted_rules = self._matchAgainstRuleList(self.blacklist,rule)
00282         self.lock.release()
00283         success = False
00284         if matched_rules and not matched_blacklisted_rules:
00285             success = True
00286         return success
00287 
00288     def _generatePublic(self, rule):
00289         '''
00290           Given a rule, determines if the rule is allowed. If it is 
00291           allowed, then returns the corresponding Rule object
00292 
00293           @param rules : the given rules to match
00294           @type Rule
00295           @return The generated Rule if allowed, None if no match
00296           @rtype Rule || None
00297         '''
00298         if self._allowRule(rule):
00299             return Rule(rule)
00300         return None
00301 
00302     def update(self,connections):
00303         '''
00304           Checks a list of rules and determines which ones should be 
00305           added/removed to the public interface. Modifies the public interface
00306           accordingly, and returns the list of rules to the gateway for
00307           hub operations
00308 
00309           @param rules: the list of rules available locally
00310           @type dict of lists of Rule objects
00311 
00312           @return: new public connections, as well as connections to be removed
00313           @rtype: Connection[], Connection[]
00314         '''
00315         # SLOW, EASY METHOD
00316         public = utils.createEmptyConnectionTypeDictionary()
00317         new_public = utils.createEmptyConnectionTypeDictionary()
00318         removed_public = utils.createEmptyConnectionTypeDictionary()
00319         diff = lambda l1,l2: [x for x in l1 if x not in l2] # diff of lists
00320         for connection_type in connections:
00321             for connection in connections[connection_type]:
00322                 if self._allowRule(connection.rule):
00323                     public[connection_type].append(connection)
00324             new_public[connection_type] = diff(public[connection_type],self.public[connection_type])
00325             removed_public[connection_type] = diff(self.public[connection_type],public[connection_type])
00326 
00327         self.lock.acquire()
00328         self.public = public
00329         self.lock.release()
00330 
00331         return new_public, removed_public
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rocon_gateway
Author(s): Daniel Stonier, Jihoon Lee,
autogenerated on Tue Jan 15 2013 17:43:24