Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 import roslib; roslib.load_manifest('rocon_gateway')
00012 from gateway_msgs.msg import RemoteRule
00013 import copy
00014 import re
00015
00016
00017 import utils
00018 import interactive_interface
00019
00020
00021
00022
00023
00024
00025 class PulledInterface(interactive_interface.InteractiveInterface):
00026 '''
00027 The flipped interface is the set of rules
00028 (pubs/subs/services/actions) and rules controlling flips
00029 to other gateways.
00030 '''
00031 def __init__(self, default_rule_blacklist, default_rules, all_targets):
00032 '''
00033 Initialises the flipped interface.
00034
00035 @param default_rule_blacklist : used when in flip all mode
00036 @type dictionary of gateway
00037 @param default_rules : static rules to pull on startup
00038 @type gateway_msgs.msg.RemoteRule[]
00039 @param all_targets : static pull all targets to pull to on startup
00040 @type string[]
00041 '''
00042 interactive_interface.InteractiveInterface.__init__(self,default_rule_blacklist, default_rules, all_targets)
00043
00044
00045 self.pulled = self.active
00046 self.pull_all = self.add_all
00047 self.unpull_all = self.remove_all
00048
00049 def update(self,connections, gateway,unique_name):
00050 '''
00051 Computes a new pulled interface from the incoming connections list
00052 and returns two dictionaries -
00053 removed and newly added pulls so the watcher thread can take
00054 appropriate action ((un)registrations).
00055
00056 This is run in the watcher thread (warning: take care - other
00057 additions come from ros service calls in different threads!)
00058 '''
00059
00060
00061 flipped = utils.createEmptyConnectionTypeDictionary()
00062 new_flips = utils.createEmptyConnectionTypeDictionary()
00063 removed_flips = utils.createEmptyConnectionTypeDictionary()
00064 diff = lambda l1,l2: [x for x in l1 if x not in l2]
00065 self._lock.acquire()
00066 for connection_type in connections:
00067 for connection in connections[connection_type]:
00068 flipped[connection_type].extend(self._generatePulls(connection.rule.type, connection.rule.name, connection.rule.node, gateway,unique_name))
00069 new_flips[connection_type] = diff(flipped[connection_type],self.pulled[connection_type])
00070 removed_flips[connection_type] = diff(self.pulled[connection_type],flipped[connection_type])
00071 self.pulled = copy.deepcopy(flipped)
00072 self._lock.release()
00073 return new_flips, removed_flips
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097 def _generatePulls(self, type, name, node, gateway,unique_name):
00098 '''
00099 Checks if a local rule (obtained from master.getSystemState)
00100 is a suitable association with any of the rules or patterns. This can
00101 return multiple matches, since the same local rule
00102 properties can be multiply flipped to different remote gateways.
00103
00104 Used in the update() call above that is run in the watcher thread.
00105
00106 Note, don't need to lock here as the update() function takes care of it.
00107
00108 @param type : rule type
00109 @type str : string constant from gateway_msgs.msg.Rule
00110
00111 @param name : fully qualified topic, service or action name
00112 @type str
00113
00114 @param node : ros node name (coming from master.getSystemState)
00115 @type str
00116
00117 @return all the pull rules that match this local rule
00118 @return list of RemoteRule objects updated with node names from self.watchlist
00119 '''
00120 matched_flip_rules = []
00121 for rule in self.watchlist[type]:
00122
00123 if gateway and not re.match(rule.gateway,gateway):
00124 continue
00125
00126 rule_name = rule.rule.name
00127 matched = self.is_matched(rule, rule_name, name, node)
00128 if not matched:
00129 rule_name = '/' + unique_name + '/' + rule.rule.name
00130 matched = self.is_matched(rule, rule_name, name, node)
00131
00132 if not matched:
00133 rule_name = '/' + rule.rule.name
00134 matched = self.is_matched(rule, rule_name, name, node)
00135
00136 if matched:
00137 matched_flip = copy.deepcopy(rule)
00138 matched_flip.rule.name = name
00139 matched_flip.rule.node = node
00140 matched_flip_rules.append(matched_flip)
00141 return matched_flip_rules
00142
00143
00144
00145
00146
00147 def list_remote_gateway_names(self):
00148 '''
00149 Collects all gateways that it should watch for (i.e. those
00150 currently handled by existing registrations).
00151
00152 @return set of gateway string ids
00153 @rtype set of string
00154 '''
00155 gateways = []
00156 for connection_type in utils.connection_types:
00157 for registration in self.registrations[connection_type]:
00158 if registration.remote_gateway not in gateways:
00159 gateways.append(registration.remote_gateway)
00160 return gateways