Package rospy :: Module timer

Source Code for Module rospy.timer

  1  # Software License Agreement (BSD License) 
  2  # 
  3  # Copyright (c) 2010, Willow Garage, Inc. 
  4  # All rights reserved. 
  5  # 
  6  # Redistribution and use in source and binary forms, with or without 
  7  # modification, are permitted provided that the following conditions 
  8  # are met: 
  9  # 
 10  #  * Redistributions of source code must retain the above copyright 
 11  #    notice, this list of conditions and the following disclaimer. 
 12  #  * Redistributions in binary form must reproduce the above 
 13  #    copyright notice, this list of conditions and the following 
 14  #    disclaimer in the documentation and/or other materials provided 
 15  #    with the distribution. 
 16  #  * Neither the name of Willow Garage, Inc. nor the names of its 
 17  #    contributors may be used to endorse or promote products derived 
 18  #    from this software without specific prior written permission. 
 19  # 
 20  # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 
 21  # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 
 22  # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 
 23  # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 
 24  # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 
 25  # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 
 26  # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 
 27  # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 
 28  # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 
 29  # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 
 30  # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 
 31  # POSSIBILITY OF SUCH DAMAGE. 
 32  # 
 33  # Revision $Id: __init__.py 12069 2010-11-09 20:31:55Z kwc $ 
 34   
 35  import threading 
 36  import time 
 37   
 38  # for Time, Duration 
 39  import genpy 
 40   
 41  import rospy.core 
 42  import rospy.rostime 
 43   
 44  # author: tfield (Timers) 
 45  # author: kwc (Rate, sleep) 
 46   
47 -class Rate(object):
48 """ 49 Convenience class for sleeping in a loop at a specified rate 50 """ 51
52 - def __init__(self, hz):
53 """ 54 Constructor. 55 @param hz: hz rate to determine sleeping 56 @type hz: int 57 """ 58 # #1403 59 self.last_time = rospy.rostime.get_rostime() 60 self.sleep_dur = rospy.rostime.Duration(0, int(1e9/hz))
61
62 - def _remaining(self, curr_time):
63 """ 64 Calculate the time remaining for rate to sleep. 65 @param curr_time: current time 66 @type curr_time: L{Time} 67 @return: time remaining 68 @rtype: L{Time} 69 """ 70 # detect time jumping backwards 71 if self.last_time > curr_time: 72 self.last_time = curr_time 73 74 # calculate remaining time 75 elapsed = curr_time - self.last_time 76 return self.sleep_dur - elapsed
77
78 - def remaining(self):
79 """ 80 Return the time remaining for rate to sleep. 81 @return: time remaining 82 @rtype: L{Time} 83 """ 84 curr_time = rospy.rostime.get_rostime() 85 return self._remaining(curr_time)
86
87 - def sleep(self):
88 """ 89 Attempt sleep at the specified rate. sleep() takes into 90 account the time elapsed since the last successful 91 sleep(). 92 93 @raise ROSInterruptException: if ROS shutdown occurs before 94 sleep completes 95 @raise ROSTimeMovedBackwardsException: if ROS time is set 96 backwards 97 """ 98 curr_time = rospy.rostime.get_rostime() 99 sleep(self._remaining(curr_time)) 100 self.last_time = self.last_time + self.sleep_dur 101 102 # detect time jumping forwards, as well as loops that are 103 # inherently too slow 104 if curr_time - self.last_time > self.sleep_dur * 2: 105 self.last_time = curr_time
106
107 -def sleep(duration):
108 """ 109 sleep for the specified duration in ROS time. If duration 110 is negative, sleep immediately returns. 111 112 @param duration: seconds (or rospy.Duration) to sleep 113 @type duration: float or Duration 114 @raise ROSInterruptException: if ROS shutdown occurs before sleep 115 completes 116 @raise ROSTimeMovedBackwardsException: if ROS time is set 117 backwards 118 """ 119 if rospy.rostime.is_wallclock(): 120 if isinstance(duration, genpy.Duration): 121 duration = duration.to_sec() 122 if duration < 0: 123 return 124 else: 125 rospy.rostime.wallsleep(duration) 126 else: 127 initial_rostime = rospy.rostime.get_rostime() 128 if not isinstance(duration, genpy.Duration): 129 duration = genpy.Duration.from_sec(duration) 130 131 rostime_cond = rospy.rostime.get_rostime_cond() 132 133 # #3123 134 if initial_rostime == genpy.Time(0): 135 # break loop if time is initialized or node is shutdown 136 while initial_rostime == genpy.Time(0) and \ 137 not rospy.core.is_shutdown(): 138 with rostime_cond: 139 rostime_cond.wait(0.3) 140 initial_rostime = rospy.rostime.get_rostime() 141 142 sleep_t = initial_rostime + duration 143 144 # break loop if sleep_t is reached, time moves backwards, or 145 # node is shutdown 146 while rospy.rostime.get_rostime() < sleep_t and \ 147 rospy.rostime.get_rostime() >= initial_rostime and \ 148 not rospy.core.is_shutdown(): 149 with rostime_cond: 150 rostime_cond.wait(0.5) 151 152 if rospy.rostime.get_rostime() < initial_rostime: 153 time_jump = (initial_rostime - rospy.rostime.get_rostime()).to_sec() 154 rospy.core.logerr("ROS time moved backwards: %ss", time_jump) 155 raise rospy.exceptions.ROSTimeMovedBackwardsException(time_jump) 156 if rospy.core.is_shutdown(): 157 raise rospy.exceptions.ROSInterruptException("ROS shutdown request")
158
159 -class TimerEvent(object):
160 """ 161 Constructor. 162 @param last_expected: in a perfect world, this is when the previous callback should have happened 163 @type last_expected: rospy.Time 164 @param last_real: when the callback actually happened 165 @type last_real: rospy.Time 166 @param current_expected: in a perfect world, this is when the current callback should have been called 167 @type current_expected: rospy.Time 168 @param last_duration: contains the duration of the last callback (end time minus start time) in seconds. 169 Note that this is always in wall-clock time. 170 @type last_duration: float 171 """
172 - def __init__(self, last_expected, last_real, current_expected, current_real, last_duration):
173 self.last_expected = last_expected 174 self.last_real = last_real 175 self.current_expected = current_expected 176 self.current_real = current_real 177 self.last_duration = last_duration
178
179 -class Timer(threading.Thread):
180 """ 181 Convenience class for calling a callback at a specified rate 182 """ 183
184 - def __init__(self, period, callback, oneshot=False):
185 """ 186 Constructor. 187 @param period: desired period between callbacks 188 @type period: rospy.Duration 189 @param callback: callback to be called 190 @type callback: function taking rospy.TimerEvent 191 @param oneshot: if True, fire only once, otherwise fire continuously until shutdown is called [default: False] 192 @type oneshot: bool 193 """ 194 super(Timer, self).__init__() 195 self._period = period 196 self._callback = callback 197 self._oneshot = oneshot 198 self._shutdown = False 199 self.setDaemon(True) 200 self.start()
201
202 - def shutdown(self):
203 """ 204 Stop firing callbacks. 205 """ 206 self._shutdown = True
207
208 - def run(self):
209 r = Rate(1.0 / self._period.to_sec()) 210 current_expected = rospy.rostime.get_rostime() + self._period 211 last_expected, last_real, last_duration = None, None, None 212 while not rospy.core.is_shutdown() and not self._shutdown: 213 try: 214 r.sleep() 215 except rospy.exceptions.ROSInterruptException as e: 216 if rospy.core.is_shutdown(): 217 break 218 raise 219 if self._shutdown: 220 break 221 current_real = rospy.rostime.get_rostime() 222 start = time.time() 223 self._callback(TimerEvent(last_expected, last_real, current_expected, current_real, last_duration)) 224 if self._oneshot: 225 break 226 last_duration = time.time() - start 227 last_expected, last_real = current_expected, current_real 228 current_expected += self._period
229