Package rocon_gateway :: Module watcher_thread
[frames] | no frames]

Source Code for Module rocon_gateway.watcher_thread

 1  #!/usr/bin/env python 
 2  # 
 3  # License: BSD 
 4  #   https://raw.github.com/robotics-in-concert/rocon_multimaster/hydro-devel/rocon_gateway/LICENSE 
 5  # 
 6  ############################################################################## 
 7  # Imports 
 8  ############################################################################## 
 9   
10  import rospy 
11  import httplib 
12   
13  ############################################################################## 
14  # Watcher 
15  ############################################################################## 
16   
17   
18 -class WatcherThread(object):
19 ''' 20 This used to be on a thread of its own, but now moved into 21 the gateway's main thread for running. 22 ''' 23
24 - def __init__(self, gateway, watch_loop_period):
25 self.trigger_update = False 26 self._trigger_shutdown = False 27 self._gateway = gateway 28 self._master = gateway.master 29 self._hub_manager = gateway.hub_manager 30 self._hubs = self._hub_manager.hubs 31 self._flipped_interface = gateway.flipped_interface 32 self._pulled_interface = gateway.pulled_interface 33 self._default_watch_loop_period = rospy.Duration(watch_loop_period) 34 self._watch_loop_period = rospy.Duration(watch_loop_period) 35 self._last_loop_timestamp = rospy.Time.now() 36 self._internal_sleep_period = rospy.Duration(0, 200000000) # 200ms
37
38 - def set_watch_loop_period(self, period):
39 ''' 40 This is used via the gateway node service to configure the rate of the 41 watcher thread. If not positive, it will reset to the default. 42 43 @param period : new setting in seconds 44 @type float 45 ''' 46 self._watch_loop_period = self._default_watch_loop_period if period <= 0.0 else rospy.Duration(period)
47
48 - def get_watch_loop_period(self):
49 ''' 50 Use Duration's to_sec() method to convert this to float. 51 52 @return the watcher loop period. 53 @rtype rospy.Duration 54 ''' 55 return self._watch_loop_period
56
57 - def start(self):
58 ''' 59 The watcher thread - monitors both the local master's system state (list of connections) 60 and the various rules to make sure rules and existing connections or flips are in sync. 61 ''' 62 while not rospy.is_shutdown(): 63 # don't waste time processing if we're not connected to at least one hub 64 if self._gateway.is_connected(): 65 try: 66 connections = self._master.get_connection_state() 67 except httplib.ResponseNotReady: 68 rospy.logwarn("Gateway : received 'ResponseNotReady' from master api") 69 self._sleep() 70 continue 71 remote_gateway_hub_index = self._hub_manager.create_remote_gateway_hub_index() 72 self._gateway.update_flipped_interface(connections, remote_gateway_hub_index) 73 self._gateway.update_public_interface(connections) 74 self._gateway.update_pulled_interface(connections, remote_gateway_hub_index) 75 self._sleep()
76
77 - def _sleep(self):
78 ''' 79 Internal interruptible sleep loop to check for shutdown and update triggers. 80 This lets us set a really long watch_loop update if we wish. 81 ''' 82 while not rospy.is_shutdown() and not self.trigger_update and (rospy.Time.now() - self._last_loop_timestamp < self._watch_loop_period): 83 rospy.sleep(self._internal_sleep_period) 84 self.trigger_update = False 85 self._last_loop_timestamp = rospy.Time.now()
86