flipped_interface.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # License: BSD
4 # https://raw.github.com/robotics-in-concert/rocon_multimaster/license/LICENSE
5 #
6 ##############################################################################
7 # Imports
8 ##############################################################################
9 
10 import copy
11 import re
12 import socket
13 
14 import rospy
15 import rosgraph
16 import rocon_gateway_utils
17 from gateway_msgs.msg import RemoteRuleWithStatus
18 
19 from . import utils
20 from . import interactive_interface
21 
22 ##############################################################################
23 # Flipped Interface
24 ##############################################################################
25 
26 
28 
29  '''
30  The flipped interface is the set of rules
31  (pubs/subs/services/actions) and rules controlling flips
32  to other gateways.
33  '''
34 
35  def __init__(self, firewall, default_rule_blacklist, default_rules, all_targets):
36  '''
37  Initialises the flipped interface.
38 
39  @param firewall : flag to prevent this gateway from accepting flips
40  @type Bool
41  @param default_rule_blacklist : used when in flip all mode
42  @type dictionary of gateway
43  @param default_rules : static rules to flip on startup
44  @type gateway_msgs.msg.RemoteRule[]
45  @param all_targets : static flip all targets to flip to on startup
46  @type string[]
47 
48  '''
49  interactive_interface.InteractiveInterface.__init__(self, default_rule_blacklist, default_rules, all_targets)
50 
51  self.firewall = firewall
52 
53  # Function aliases
54  self.flipped = self.active
55  self.filtered_flips = []
56  self.flip_status = utils.create_empty_connection_type_dictionary()
57  self.flip_all = self.add_all
58  self.unflip_all = self.remove_all
59 
60  ##########################################################################
61  # Monitoring
62  ##########################################################################
63 
64  def update(self, connections, remote_gateway_hub_index, unique_name, master):
65  '''
66  Computes a new flipped interface and returns two dictionaries -
67  removed and newly added flips so the watcher thread can take
68  appropriate action (inform the remote gateways).
69 
70  This is run in the watcher thread (warning: take care - other
71  additions come from ros service calls in different threads!)
72 
73  @param connections : list of all the system state connections from the local master
74  @type connection type keyed dictionary of utils.Connection sets.
75 
76  @param remote_gateway_hub_index : full gateway-hub database index to parse
77  @type gateway hash names keyed into a dic with a list of their hubs
78 
79  @param unique_name : this gateway's unique hash name
80  @type string
81 
82  @param master : local master
83  @type rocon_gateway.LocalMaster
84 
85  @return new_flips, removed_flips (i.e. those that are no longer on the local master)
86  @rtype pair of connection type keyed dictionary of gateway_msgs.msg.Rule lists.
87  '''
88  # SLOW, EASY METHOD
89  remote_gateways = remote_gateway_hub_index.keys()
90 
91  self._lock.acquire()
92 
93  # Prune locally cached flip list for flips that have lost their remotes, keep the rules though
94  self.flipped = self._prune_unavailable_gateway_flips(self.flipped, remote_gateways)
95 
96  # Totally regenerate a new flipped interface, compare with old
97  new_flips, removed_flips, flipped = self._prepare_flips(connections, remote_gateways, unique_name, master)
98 
99  flip_status = self._prepare_flip_status(flipped)
100  new_flips, filtered_flips = self._filter_flipped_in_interfaces(new_flips, self.registrations)
101  #rospy.loginfo("new_flips : {nf}".format(nf=new_flips))
102  self.flipped = self._update_flipped(flipped, filtered_flips)
103  self._lock.release()
104  return new_flips, removed_flips
105 
106  # OPTIMISED METHOD
107  # Keep old rule state and old flip rules/patterns around
108  #
109  # 1 - If flip rules/patterns disappeared [diff(old_rules,new_rules)]
110  # Check if the current flips are still valid
111  # If not all are, remove and unflip them
112  #
113  # 2 - If rules disappeared [diff(old_conns,new_conns)]
114  # If matching any in flipped, remove and unflip
115  #
116  # 3 - If flip rules/patterns appeared [diff(new_rules,old_rules)]
117  # parse all conns, if match found, flip
118  #
119  # 4 - If rules appeared [diff(new_conns,old_conns)]
120  # check for matches, if found, flou
121  #
122  # utils.difflist = lambda l1,l2: [x for x in l1 if x not in l2] # diff of lists
123 
124  def _update_flipped(self, flipped, filtered_flips):
125  updated_flipped = {}
126  for connection_type in flipped.keys():
127  updated_flipped[connection_type] = [copy.deepcopy(r) for r in flipped[connection_type] if not r in filtered_flips[connection_type]]
128  return updated_flipped
129 
130  def _filter_flipped_in_interfaces(self, new_flips, flipped_in_registrations):
131  '''
132  Gateway should not flip out the flipped-in interface.
133  '''
134  filtered_flips = utils.create_empty_connection_type_dictionary()
135  for connection_type in utils.connection_types:
136  for rule in flipped_in_registrations[connection_type]:
137  r = self._is_registration_in_remote_rule(rule, new_flips[connection_type])
138  if r:
139  filtered_flips[connection_type].append(r)
140 
141  for connection_type in new_flips.keys():
142  new_flips[connection_type] = [r for r in new_flips[connection_type] if not r in filtered_flips[connection_type]]
143 
144  rospy.logdebug("Gateway : filtered flip list to prevent cyclic flipping - %s"%str(filtered_flips))
145 
146  return new_flips, filtered_flips
147 
148  def _is_registration_in_remote_rule(self, rule, new_flip_remote_rules):
149  for r in new_flip_remote_rules:
150  node = r.rule.node.split(",")[0]
151  if rule.local_node == node and rule.remote_gateway == r.gateway and rule.connection.rule.name == r.rule.name:
152  return r
153  return None
154 
155  def update_flip_status(self, flip, status):
156  '''
157  Update the status of a flip from the hub. This should be called right
158  after update once self.flipped is established
159 
160  @return True if status was indeed changed, False otherwise
161  @rtype Boolean
162  '''
163  state_changed = False
164  self._lock.acquire()
165  try:
166  index = self.flipped[flip.rule.type].index(flip)
167  state_changed = (self.flip_status[flip.rule.type][index] != status)
168  self.flip_status[flip.rule.type][index] = status
169  #rospy.loginfo("self.flip_status[{t}][{i}] = {s}".format(t=flip.rule.type, i=index, s=status))
170  except ValueError:
171  pass
172  self._lock.release()
173  return state_changed
174 
175  def remove_flip(self, flip):
176  '''
177  Removes a flip, so that it can be resent as necessary
178  '''
179  self._lock.acquire()
180  try:
181  self.flipped[flip.rule.type].remove(flip)
182  except ValueError:
183  pass
184  self._lock.release()
185 
186  ##########################################################################
187  # Utility Methods
188  ##########################################################################
189 
190  def _generate_flips(self, connection_type, name, node, remote_gateways, unique_name, master):
191  '''
192  Checks if a local rule (obtained from master.get_system_state)
193  is a suitable association with any of the rules or patterns. This can
194  return multiple matches, since the same local rule
195  properties can be multiply flipped to different remote gateways.
196 
197  Used in the update() call above that is run in the watcher thread.
198  Note, don't need to lock here as the update() function takes care of it.
199 
200  @param connection_type : rule type
201  @type str : string constant from gateway_msgs.msg.Rule
202 
203  @param name : fully qualified topic, service or action name
204  @type str
205 
206  @param node : ros node name (coming from master.get_system_state)
207  @type str
208 
209  @param gateways : gateways that are available (registered on the hub)
210  @type string
211 
212  @param master : local master
213  @type rocon_gateway.LocalMaster
214 
215  @return all the flip rules that match this local rule
216  @return list of RemoteRule objects updated with node names from self.watchlist
217  '''
218  matched_flip_rules = []
219  for flip_rule in self.watchlist[connection_type]:
220  # Check if the flip rule corresponds to an existing gateway
221  matched_gateways = self._get_matched_gateways(flip_rule, remote_gateways)
222  if not matched_gateways:
223  continue
224 
225  # Check names
226  rule_name = flip_rule.rule.name
227  matched = self.is_matched(flip_rule, rule_name, name, node)
228 
229  if not utils.is_all_pattern(flip_rule.rule.name):
230  if not matched:
231  rule_name = '/' + unique_name + '/' + flip_rule.rule.name
232  matched = self.is_matched(flip_rule, rule_name, name, node)
233 
234  # If it is still not matching
235  if not matched:
236  rule_name = '/' + flip_rule.rule.name
237  matched = self.is_matched(flip_rule, rule_name, name, node)
238 
239  if matched:
240  for gateway in matched_gateways:
241  try:
242  matched_flip = copy.deepcopy(flip_rule)
243  matched_flip.gateway = gateway # just in case we used a regex or matched basename
244  matched_flip.rule.name = name # just in case we used a regex
245  matched_flip.rule.node = "%s,%s"%(node, master.lookupNode(node)) # just in case we used a regex
246  matched_flip_rules.append(matched_flip)
247  except rosgraph.masterapi.MasterError as e:
248  # Node has been gone already. skips sliently
249  pass
250  except socket.error as e:
251  rospy.logwarn("Gateway : socket error while generate flips [%s]"%str(e))
252  return matched_flip_rules
253 
254  def _prune_unavailable_gateway_flips(self, flipped, remote_gateways):
255  # Prune locally cached flip list for flips that have lost their remotes, keep the rules though
256  for connection_type in utils.connection_types:
257  # flip.gateway is a hash name, so is the remote_gateways list
258  flipped[connection_type] = [flip for flip in self.flipped[connection_type] if flip.gateway in remote_gateways]
259  return flipped
260 
261  def _prepare_flips(self, connections, remote_gateways, unique_name, master):
262  # Variable preparations
263  flipped = utils.create_empty_connection_type_dictionary()
264  new_flips = utils.create_empty_connection_type_dictionary()
265  removed_flips = utils.create_empty_connection_type_dictionary()
266 
267  for connection_type in connections:
268  for connection in connections[connection_type]:
269  matched_flip_rules = self._generate_flips(connection.rule.type, connection.rule.name, connection.rule.node, remote_gateways, unique_name, master)
270  flipped[connection_type].extend(matched_flip_rules)
271 
272  new_flips[connection_type] = utils.difflist(flipped[connection_type], self.flipped[connection_type])
273  removed_flips[connection_type] = utils.difflist(self.flipped[connection_type], flipped[connection_type])
274  return new_flips, removed_flips, flipped
275 
276  def _prepare_flip_status(self, flipped):
277  flip_status = utils.create_empty_connection_type_dictionary()
278 
279  # set flip status to unknown first, and then read previous status if available
280  for connection_type in utils.connection_types:
281  flip_status[connection_type] = [RemoteRuleWithStatus.UNKNOWN] * len(flipped[connection_type])
282 
283  for connection_type in utils.connection_types:
284  #rospy.loginfo("flip_status[{ct}] = {f}".format(ct=connection_type, f=flip_status[connection_type]))
285  #rospy.loginfo("flipped[{ct}] = {f}".format(ct=connection_type, f=flipped[connection_type]))
286  for new_index, flip in enumerate(flipped[connection_type]):
287  try:
288  index = self.flipped[connection_type].index(flip)
289  flip_status[connection_type][new_index] = self.flip_status[connection_type][index]
290  #rospy.loginfo("flipped[{idx}].status == {status}".format(idx=new_index, status=flip_status[connection_type][new_index]))
291  except:
292  # The new flip probably did not exist. Let it remain unknown
293  pass
294  self.flip_status = copy.deepcopy(flip_status)
295 
296  return flip_status
297 
298  def _get_matched_gateways(self, flip_rule, remote_gateways):
299  matched_gateways = []
300  for gateway in remote_gateways:
301  # check for regular expression or perfect match
302  gateway_match_result = re.match(flip_rule.gateway, gateway)
303  if gateway_match_result and gateway_match_result.group() == gateway:
304  matched_gateways.append(gateway)
305  elif flip_rule.gateway == rocon_gateway_utils.gateway_basename(gateway):
306  matched_gateways.append(gateway)
307  return matched_gateways
308 
309 
310  ##########################################################################
311  # Accessors for Gateway Info
312  ##########################################################################
314  '''
315  Gets the flipped connections list for GatewayInfo consumption.
316 
317  @return the list of flip rules that are activated and have been flipped.
318  @rtype RemoteRule[]
319  '''
320  flipped_connections = []
321  for connection_type in utils.connection_types:
322  for i, connection in enumerate(self.flipped[connection_type]):
323  flipped_connections.append(RemoteRuleWithStatus(connection, self.flip_status[connection_type][i]))
324  return flipped_connections
325 
326 
327 if __name__ == "__main__":
328 
329  gateways = ['dude', 'dudette']
330  dudes = ['fred', 'dude']
331  dudes[:] = [x for x in dudes if x in gateways]
332  print dudes
def _filter_flipped_in_interfaces(self, new_flips, flipped_in_registrations)
def _prepare_flips(self, connections, remote_gateways, unique_name, master)
def is_matched(self, rule, rule_name, name, node)
Accessors for Gateway Info.
def get_flipped_connections(self)
Accessors for Gateway Info.
def _update_flipped(self, flipped, filtered_flips)
def _get_matched_gateways(self, flip_rule, remote_gateways)
def _generate_flips(self, connection_type, name, node, remote_gateways, unique_name, master)
Utility Methods.
def _is_registration_in_remote_rule(self, rule, new_flip_remote_rules)
def _prune_unavailable_gateway_flips(self, flipped, remote_gateways)
def update(self, connections, remote_gateway_hub_index, unique_name, master)
Monitoring.
def __init__(self, firewall, default_rule_blacklist, default_rules, all_targets)


rocon_gateway
Author(s): Daniel Stonier , Jihoon Lee , Piyush Khandelwal
autogenerated on Mon Jun 10 2019 14:40:10