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/license/LICENSE
00005 #
00006 ##############################################################################
00007 # Imports
00008 ##############################################################################
00009 
00010 import httplib
00011 import rospy
00012 import time
00013 
00014 ##############################################################################
00015 # Watcher
00016 ##############################################################################
00017 
00018 
00019 class WatcherThread(object):
00020 
00021     '''
00022       This used to be on a thread of its own, but now moved into
00023       the gateway's main thread for running.
00024     '''
00025 
00026     def __init__(self, gateway, watch_loop_period):
00027         self.trigger_update = False
00028         self._trigger_shutdown = False
00029         self._gateway = gateway
00030         self._master = gateway.master
00031         self._hub_manager = gateway.hub_manager
00032         self._hubs = self._hub_manager.hubs
00033         self._flipped_interface = gateway.flipped_interface
00034         self._pulled_interface = gateway.pulled_interface
00035         self._default_watch_loop_period = watch_loop_period
00036         self._watch_loop_period = watch_loop_period
00037         self._last_loop_timestamp = time.time()
00038         self._internal_sleep_period = 0.2  # 200ms
00039 
00040     def set_watch_loop_period(self, period):
00041         '''
00042           This is used via the gateway node service to configure the rate of the
00043           watcher thread. If not positive, it will reset to the default.
00044 
00045           @param period : new setting in seconds
00046           @type float
00047         '''
00048         self._watch_loop_period = self._default_watch_loop_period if period <= 0.0 else period
00049 
00050     def get_watch_loop_period(self):
00051         '''
00052           Use Duration's to_sec() method to convert this to float.
00053 
00054           @return the watcher loop period.
00055           @rtype float
00056         '''
00057         return self._watch_loop_period
00058 
00059     def start(self):
00060         '''
00061           The watcher thread - monitors both the local master's system state (list of connections)
00062           and the various rules to make sure rules and existing connections or flips are in sync.
00063         '''
00064         while not rospy.is_shutdown():
00065             # don't waste time processing if we're not connected to at least one hub
00066             if self._gateway.is_connected():
00067                 try:
00068                     connections = self._master.get_connection_state()
00069                 except httplib.ResponseNotReady:
00070                     rospy.logwarn("Gateway : received 'ResponseNotReady' from master api")
00071                     self._sleep()
00072                     continue
00073                 remote_gateway_hub_index = self._hub_manager.create_remote_gateway_hub_index()
00074                 self._gateway.update_network_information()
00075                 self._gateway.update_flipped_interface(connections, remote_gateway_hub_index)
00076                 self._gateway.update_public_interface(connections)
00077                 self._gateway.update_pulled_interface(connections, remote_gateway_hub_index)
00078                 registrations = self._hub_manager.get_flip_requests()
00079                 self._gateway.update_flipped_in_interface(registrations, remote_gateway_hub_index)
00080             self._sleep()
00081 
00082     def _sleep(self):
00083         '''
00084           Internal non-interruptible sleep loop to check for shutdown and update triggers.
00085           This lets us set a really long watch_loop update if we wish.
00086         '''
00087         while (not rospy.is_shutdown() and not self.trigger_update and
00088                (time.time() - self._last_loop_timestamp < self._watch_loop_period)):
00089             rospy.rostime.wallsleep(self._internal_sleep_period)
00090         self.trigger_update = False
00091         self._last_loop_timestamp = time.time()


rocon_gateway
Author(s): Daniel Stonier , Jihoon Lee , Piyush Khandelwal
autogenerated on Sat Jun 8 2019 18:48:44