Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import threading
00036 import time
00037
00038 import roslib.rostime
00039
00040 import rospy.core
00041 import rospy.rostime
00042 import rospy
00043
00044
00045
00046
00047 class TimerEvent(object):
00048 """
00049 Constructor.
00050 @param last_expected: in a perfect world, this is when the previous callback should have happened
00051 @type last_expected: rospy.Time
00052 @param last_real: when the callback actually happened
00053 @type last_real: rospy.Time
00054 @param current_expected: in a perfect world, this is when the current callback should have been called
00055 @type current_expected: rospy.Time
00056 @param last_duration: contains the duration of the last callback (end time minus start time) in seconds.
00057 Note that this is always in wall-clock time.
00058 @type last_duration: float
00059 """
00060 def __init__(self, last_expected, last_real, current_expected, current_real, last_duration):
00061 self.last_expected = last_expected
00062 self.last_real = last_real
00063 self.current_expected = current_expected
00064 self.current_real = current_real
00065 self.last_duration = last_duration
00066
00067 class Timer(threading.Thread):
00068 """
00069 Convenience class for calling a callback at a specified rate
00070 """
00071
00072 def __init__(self, period, callback, oneshot=False):
00073 """
00074 Constructor.
00075 @param period: desired period between callbacks
00076 @type period: rospy.Time
00077 @param callback: callback to be called
00078 @type callback: function taking rospy.TimerEvent
00079 @param oneshot: if True, fire only once, otherwise fire continuously until shutdown is called [default: False]
00080 @type oneshot: bool
00081 """
00082 threading.Thread.__init__(self)
00083 self._period = period
00084 self._callback = callback
00085 self._oneshot = oneshot
00086 self._shutdown = False
00087 self.setDaemon(True)
00088 self.start()
00089
00090 def shutdown(self):
00091 """
00092 Stop firing callbacks.
00093 """
00094 self._shutdown = True
00095
00096 def run(self):
00097 r = rospy.Rate(1.0 / self._period.to_sec())
00098 current_expected = rospy.rostime.get_rostime() + self._period
00099 last_expected, last_real, last_duration = None, None, None
00100 while not rospy.core.is_shutdown() and not self._shutdown:
00101 r.sleep()
00102 current_real = rospy.rostime.get_rostime()
00103 start = time.time()
00104 self._callback(TimerEvent(last_expected, last_real, current_expected, current_real, last_duration))
00105 if self._oneshot:
00106 break
00107 last_duration = time.time() - start
00108 last_expected, last_real = current_expected, current_real
00109 current_expected += self._period
hrl_lib
Author(s): Cressel Anderson, Travis Deyle, Advait Jain, Hai Nguyen, Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 11:34:06