Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 import copy
00012 import re
00013
00014
00015 import threading
00016 threading._DummyThread._Thread__stop = lambda x: 42
00017
00018 import rospy
00019 from gateway_msgs.msg import Rule
00020
00021 from . import utils
00022
00023
00024
00025
00026
00027
00028 def publicRuleExists(public_rule, public_rules):
00029 '''
00030 Checks that the public rule doesn't already exist in the list of public
00031 rules (which can represent the public interface or the rules themselves).
00032 We only need to compare the name/node as they uniquely identify the
00033 name/regex
00034
00035 @param public_rule : the rule to search for
00036 @type Rule
00037
00038 @param public_rules : list of Rule (public, watchlist or blacklist)
00039 @type list : list of Rule objects
00040
00041 @return True if the public rule exists, False otherwise
00042 @rtype bool
00043 '''
00044 for rule in public_rules:
00045 if rule.name == public_rule.name and \
00046 rule.node == public_rule.node:
00047 return True
00048 return False
00049
00050
00051
00052
00053
00054
00055 class PublicInterface(object):
00056
00057 '''
00058 The public interface is the set of rules
00059 (pubs/subs/services/actions) that are exposed and made available for
00060 freely sharing with a multimaster system.
00061
00062 It consists of:
00063 * list of currently available rules to be shared
00064 * list of rules and filters that will be watched
00065 and shared if they become available
00066 '''
00067
00068 def __init__(self, default_rule_blacklist, default_rules):
00069 '''
00070 Initialises the public interface
00071
00072 @param default_rule_blacklist : connection type keyed dictionary of rules
00073 @type str keyed dictionary of gateway_msgs.msg.Rule[]
00074
00075 @param default_rules : connection type keyed dictionary of rules
00076 @type str keyed dictionary of gateway_msgs.msg.Rule[]
00077 '''
00078
00079
00080 self.watchlist = utils.create_empty_connection_type_dictionary()
00081
00082
00083 self._default_blacklist = default_rule_blacklist
00084
00085
00086 self.blacklist = self._default_blacklist
00087
00088
00089
00090 self.public = utils.create_empty_connection_type_dictionary()
00091
00092 self.advertise_all_enabled = False
00093
00094 self.lock = threading.Lock()
00095
00096
00097 for connection_type in utils.connection_types:
00098 for rule in default_rules[connection_type]:
00099 self.add_rule(rule)
00100
00101
00102
00103
00104
00105 def add_rule(self, rule):
00106 '''
00107 Watch for a new public rule, as described for by the incoming message.
00108
00109 @param rule : a rule msg from the advertise call
00110 @type Rule
00111
00112 @return the rule if added, or None if the rule exists already
00113 @rtype Rule || None
00114 '''
00115 result = None
00116 self.lock.acquire()
00117 if not publicRuleExists(rule, self.watchlist[rule.type]):
00118 self.watchlist[rule.type].append(rule)
00119 result = rule
00120 self.lock.release()
00121 rospy.loginfo("Gateway : adding rule to public watchlist %s" % utils.format_rule(rule))
00122 return result
00123
00124 def remove_rule(self, rule):
00125 '''
00126 Attempt to remove a watchlist rule from the public interface. Be a
00127 bit careful looking for a rule to remove, depending on the node name,
00128 which can be set (exact rule/node name match) or None in which case all
00129 nodes of that kind of advertisement will match.
00130
00131 @param rule : a rule to unadvertise
00132 @type Rule
00133
00134 @return the list of rules removed
00135 @rtype Rule[]
00136 '''
00137
00138 rospy.loginfo("Gateway : (req) unadvertise %s" % utils.format_rule(rule))
00139
00140 if rule.node:
00141
00142 try:
00143 self.lock.acquire()
00144 self.watchlist[rule.type].remove(rule)
00145 self.lock.release()
00146 return [rule]
00147 except ValueError:
00148 self.lock.release()
00149 return []
00150 else:
00151
00152
00153 existing_rules = []
00154 self.lock.acquire()
00155 for existing_rule in self.watchlist[rule.type]:
00156 if (existing_rule.name == rule.name):
00157 existing_rules.append(existing_rule)
00158 for rule in existing_rules:
00159 self.watchlist[rule.type].remove(existing_rule)
00160 self.lock.release()
00161 return existing_rules
00162
00163 def advertise_all(self, blacklist):
00164 '''
00165 Allow all rules apart from the ones in the provided blacklist +
00166 default blacklist
00167
00168 @param blacklist : list of Rule objects
00169 @type list : list of Rule objects
00170
00171 @return failure if already advertising all, success otherwise
00172 @rtype bool
00173 '''
00174 rospy.loginfo("Gateway : received a request advertise everything!")
00175 self.lock.acquire()
00176
00177
00178 if self.advertise_all_enabled:
00179 self.lock.release()
00180 return False
00181 self.advertise_all_enabled = True
00182
00183
00184 self.watchlist = utils.create_empty_connection_type_dictionary()
00185 for connection_type in utils.connection_types:
00186 allow_all_rule = Rule()
00187 allow_all_rule.name = '.*'
00188 allow_all_rule.type = connection_type
00189 allow_all_rule.node = '.*'
00190 self.watchlist[connection_type].append(allow_all_rule)
00191
00192
00193 self.blacklist = copy.deepcopy(self._default_blacklist)
00194 for rule in blacklist:
00195 if not publicRuleExists(rule, self.blacklist[rule.type]):
00196 self.blacklist[rule.type].append(rule)
00197
00198 self.lock.release()
00199 return True
00200
00201 def unadvertise_all(self):
00202 '''
00203 Disallow the allow all mode, if enabled. If allow all mode is not
00204 enabled, remove everything from the public interface
00205 '''
00206 rospy.loginfo("Gateway : received a request to remove all advertisements!")
00207 self.lock.acquire()
00208
00209
00210 self.advertise_all_enabled = False
00211
00212
00213 self.watchlist = utils.create_empty_connection_type_dictionary()
00214 self.blacklist = self._default_blacklist
00215
00216 self.lock.release()
00217
00218
00219
00220
00221
00222 def getConnections(self):
00223 '''
00224 List of all rules with connection information that is being published.
00225
00226 @return dictionary of utils.Connections keyed by type.
00227 '''
00228 return self.public
00229
00230 def getInterface(self):
00231 '''
00232 List of all rules currently being advertised.
00233
00234 @return list of all connections posted on hubs
00235 @rtype list of gateway_msgs.msg.Rule
00236 '''
00237 l = []
00238 self.lock.acquire()
00239 for connection_type in utils.connection_types:
00240 l.extend([connection.rule for connection in self.public[connection_type]])
00241 self.lock.release()
00242 return l
00243
00244 def getWatchlist(self):
00245 l = []
00246 self.lock.acquire()
00247 for connection_type in utils.connection_types:
00248 l.extend(self.watchlist[connection_type])
00249 self.lock.release()
00250 return l
00251
00252 def getBlacklist(self):
00253 l = []
00254 self.lock.acquire()
00255 for connection_type in utils.connection_types:
00256 l.extend(self.blacklist[connection_type])
00257 self.lock.release()
00258 return l
00259
00260
00261
00262
00263
00264 def _matchAgainstRuleList(self, rules, rule):
00265 '''
00266 Match a given rule/rule against a given rule list
00267
00268 @param rules : the rules against which to match
00269 @type dict of list of Rule objects
00270 @param rule : the given rule/rule to match
00271 @type Rule
00272 @return the list of rules matched, None if no rules found
00273 @rtype list of Rules || None
00274 '''
00275 matched = False
00276 for r in rules[rule.type]:
00277 name_match_result = re.match(r.name, rule.name)
00278 if name_match_result and name_match_result.group() == rule.name:
00279 if r.node:
00280 node_match_result = re.match(r.node, rule.node)
00281 if node_match_result and node_match_result.group() == rule.node:
00282 matched = True
00283 else:
00284 matched = True
00285 if matched:
00286 break
00287 return matched
00288
00289 def _allowRule(self, rule):
00290 '''
00291 Determines whether a given rule should be allowed given the
00292 status of the current watchlist and blacklist
00293
00294 @param rule : the given rule/rule to match
00295 @type Rule
00296 @return whether rule is allowed
00297 @rtype bool
00298 '''
00299 self.lock.acquire()
00300 matched_rules = self._matchAgainstRuleList(self.watchlist, rule)
00301 matched_blacklisted_rules = self._matchAgainstRuleList(self.blacklist, rule)
00302 self.lock.release()
00303 success = False
00304 if matched_rules and not matched_blacklisted_rules:
00305 success = True
00306 return success
00307
00308 def _generatePublic(self, rule):
00309 '''
00310 Given a rule, determines if the rule is allowed. If it is
00311 allowed, then returns the corresponding Rule object
00312
00313 @param rules : the given rules to match
00314 @type Rule
00315 @return The generated Rule if allowed, None if no match
00316 @rtype Rule || None
00317 '''
00318 if self._allowRule(rule):
00319 return Rule(rule)
00320 return None
00321
00322 def update(self, connections, generate_advertisement_connection_details):
00323 '''
00324 Checks a list of rules and determines which ones should be
00325 added/removed to the public interface. Modifies the public interface
00326 accordingly, and returns the list of rules to the gateway for
00327 hub operations
00328
00329 @param rules: the list of rules available locally
00330 @type dict of lists of Rule objects
00331
00332 @param generate_advertisement_connection_details : function from LocalMaster
00333 that generates Connection.type_info and Connection.xmlrpc_uri
00334 @type method (see LocalMaster.generate_advertisement_connection_details)
00335
00336 @return: new public connections, as well as connections to be removed
00337 @rtype: utils.Connection[], utils.Connection[]
00338 '''
00339
00340 permitted_connections = utils.create_empty_connection_type_dictionary()
00341 new_public = utils.create_empty_connection_type_dictionary()
00342 removed_public = utils.create_empty_connection_type_dictionary()
00343 for connection_type in utils.connection_types:
00344 for connection in connections[connection_type]:
00345 if self._allowRule(connection.rule):
00346 permitted_connections[connection_type].append(connection)
00347 self.lock.acquire()
00348 for connection_type in utils.connection_types:
00349 for connection in permitted_connections[connection_type]:
00350 if not connection.inConnectionList(self.public[connection_type]):
00351 new_connection = generate_advertisement_connection_details(
00352 connection.rule.type, connection.rule.name, connection.rule.node)
00353
00354
00355 if new_connection is not None:
00356 new_public[connection_type].append(new_connection)
00357 self.public[connection_type].append(new_connection)
00358 removed_public[connection_type][:] = [
00359 x for x in self.public[connection_type] if not x.inConnectionList(
00360 permitted_connections[connection_type])]
00361 self.public[connection_type][:] = [
00362 x for x in self.public[connection_type] if not x.inConnectionList(removed_public[connection_type])]
00363 self.lock.release()
00364 return new_public, removed_public