watcher_thread.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 # Imports
00008 ##############################################################################
00009 
00010 import roslib
00011 roslib.load_manifest('rocon_gateway')
00012 import rospy
00013 import threading
00014 import httplib
00015 
00016 from gateway_msgs.msg import Rule, ConnectionType
00017 from .exceptions import HubConnectionLostError
00018 
00019 ##############################################################################
00020 # Watcher
00021 ##############################################################################
00022 
00023 
00024 class WatcherThread(threading.Thread):
00025     '''
00026     '''
00027 
00028     def __init__(self, gateway, watch_loop_period):
00029         threading.Thread.__init__(self)
00030         self.trigger_update = False
00031         self._trigger_shutdown = False
00032         self._gateway = gateway
00033         self._master = gateway.master
00034         self._hub = gateway.hub
00035         #self._public_interface = gateway.public_interface
00036         self._flipped_interface = gateway.flipped_interface
00037         self._pulled_interface = gateway.pulled_interface
00038         self._watch_loop_period = rospy.Duration(watch_loop_period)
00039         self._last_loop_timestamp = rospy.Time.now()
00040         self._internal_sleep_period = rospy.Duration(0, 200000000)  # 200ms
00041         self.start()
00042 
00043     def shutdown(self):
00044         '''
00045           Called from the main program to shutdown this thread.
00046         '''
00047         self._trigger_shutdown = True
00048         self._trigger_update = True  # causes it to interrupt a sleep and drop back to check shutdown condition
00049         self.join()  # wait for the thread to finish
00050 
00051     def run(self):
00052         '''
00053           The watcher thread - monitors both the local master's system state (list of connections)
00054           and the various rules to make sure rules and existing connections or flips are in sync.
00055         '''
00056         while not rospy.is_shutdown() and not self._trigger_shutdown:
00057             if self._gateway.is_connected:
00058                 try:
00059                     connections = self._master.getConnectionState()
00060                 except httplib.ResponseNotReady:
00061                     rospy.logwarn("Gateway : received 'ResponseNotReady' from master api")
00062                     self._sleep()
00063                     continue
00064                 try:
00065                     gateways = self._hub.list_remote_gateway_names()
00066                 except HubConnectionLostError:
00067                     rospy.logwarn("Gateway : lost connection to the hub, watcher thread aborting.")
00068                     break
00069                 self._gateway.update_flip_interface(connections, gateways)
00070                 self._gateway.update_public_interface(connections)
00071                 self._gateway.update_pulled_interface(connections, gateways)
00072             self._sleep()
00073 
00074     def _sleep(self):
00075         '''
00076           Internal interruptible sleep loop to check for shutdown and update triggers.
00077           This lets us set a really long watch_loop update if we wish.
00078         '''
00079         while not rospy.is_shutdown() and not self.trigger_update and (rospy.Time.now() - self._last_loop_timestamp < self._watch_loop_period):
00080             rospy.sleep(self._internal_sleep_period)
00081         self.trigger_update = False
00082         self._last_loop_timestamp = rospy.Time.now()
 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