1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35 """
36 ROS time and duration representations, as well as internal routines
37 for managing wallclock versus a simulated clock. The important data
38 classes are L{Time} and L{Duration}, which represent the ROS 'time'
39 and 'duration' primitives, respectively.
40 """
41
42 import sys
43 import threading
44 import time
45 import traceback
46
47 import rospy.exceptions
48
49 import roslib.rosenv
50 import roslib.rostime
51
52
53
54
55 _rostime_initialized = False
56 _rostime_current = None
57 _rostime_cond = threading.Condition()
58
59
61 """
62 Duration represents the ROS 'duration' primitive type, which
63 consists of two integers: seconds and nanoseconds. The Duration
64 class allows you to add and subtract Duration instances, including
65 adding and subtracting from L{Time} instances.
66
67 Usage::
68 five_seconds = Duration(5)
69 five_nanoseconds = Duration(0, 5)
70
71 print 'Fields are', five_seconds.secs, five_seconds.nsecs
72
73 # Duration arithmetic
74 ten_seconds = five_seconds + five_seconds
75 five_secs_ago = rospy.Time.now() - five_seconds # Time minus Duration is a Time
76
77 true_val = ten_second > five_seconds
78 """
79 __slots__ = []
80
82 """
83 Create new Duration instance. secs and nsecs are integers and
84 correspond to the ROS 'duration' primitive type.
85
86 @param secs: seconds
87 @type secs: int
88 @param nsecs: nanoseconds
89 @type nsecs: int
90 """
91 roslib.rostime.Duration.__init__(self, secs, nsecs)
92
93 -class Time(roslib.rostime.Time):
94 """
95 Time represents the ROS 'time' primitive type, which consists of two
96 integers: seconds since epoch and nanoseconds since seconds. Time
97 instances are mutable.
98
99 The L{Time.now()} factory method can initialize Time to the
100 current ROS time and L{from_sec()} can be used to create a
101 Time instance from the Python's time.time() float seconds
102 representation.
103
104 The Time class allows you to subtract Time instances to compute
105 Durations, as well as add Durations to Time to create new Time
106 instances.
107
108 Usage::
109 now = rospy.Time.now()
110 zero_time = rospy.Time()
111
112 print 'Fields are', now.secs, now.nsecs
113
114 # Time arithmetic
115 five_secs_ago = now - rospy.Duration(5) # Time minus Duration is a Time
116 five_seconds = now - five_secs_ago # Time minus Time is a Duration
117 true_val = now > five_secs_ago
118
119 # NOTE: in general, you will want to avoid using time.time() in ROS code
120 import time
121 py_time = rospy.Time.from_sec(time.time())
122 """
123 __slots__ = []
124
126 """
127 Constructor: secs and nsecs are integers and correspond to the
128 ROS 'time' primitive type. You may prefer to use the static
129 L{from_sec()} and L{now()} factory methods instead.
130
131 @param secs: seconds since epoch
132 @type secs: int
133 @param nsecs: nanoseconds since seconds (since epoch)
134 @type nsecs: int
135 """
136 roslib.rostime.Time.__init__(self, secs, nsecs)
137
139 """
140 Create new L{Time} instance representing current time. This
141 can either be wall-clock time or a simulated clock. It is
142 strongly recommended that you use the now() factory to create
143 current time representations instead of reading wall-clock
144 time and create Time instances from it.
145
146 @return: L{Time} instance for current time
147 @rtype: L{Time}
148 """
149 if not _rostime_initialized:
150 raise rospy.exceptions.ROSInitException("time is not initialized. Have you called init_node()?")
151 if _rostime_current is not None:
152
153 return _rostime_current
154 else:
155
156 float_secs = time.time()
157 secs = int(float_secs)
158 nsecs = int((float_secs - secs) * 1000000000)
159 return Time(secs, nsecs)
160
161 now = staticmethod(now)
162
163
164
166 """
167 Use Time.from_sec() instead. Retained for backwards compatibility.
168
169 @param float_secs: time value in time.time() format
170 @type float_secs: float
171 @return: Time instance for specified time
172 @rtype: L{Time}
173 """
174 return Time.from_sec(float_secs)
175
176 from_seconds = staticmethod(from_seconds)
177
179 """
180 Create new Time instance from a float seconds representation
181 (e.g. time.time()).
182
183 @param float_secs: time value in time.time() format
184 @type float_secs: float
185 @return: Time instance for specified time
186 @rtype: L{Time}
187 """
188 secs = int(float_secs)
189 nsecs = int((float_secs - secs) * 1000000000)
190 return Time(secs, nsecs)
191
192 from_sec = staticmethod(from_sec)
193
207
209 """
210 Get the current time as a L{Time} object
211 @return: current time as a L{rospy.Time} object
212 @rtype: L{Time}
213 """
214 return Time.now()
215
217 """
218 Get the current time as float secs (time.time() format)
219 @return: time in secs (time.time() format)
220 @rtype: float
221 """
222 return Time.now().to_sec()
223
225 """
226 Internal use.
227 Mark rostime as initialized. This flag enables other routines to
228 throw exceptions if rostime is being used before the underlying
229 system is initialized.
230 @param val: value for initialization state
231 @type val: bool
232 """
233 global _rostime_initialized
234 _rostime_initialized = val
235
237 """
238 Internal use.
239 @return: True if rostime has been initialized
240 @rtype: bool
241 """
242 return _rostime_initialized
243
245 """
246 internal API for helper routines that need to wait on time updates
247 @return: rostime conditional var
248 @rtype: threading.Cond
249 """
250 return _rostime_cond
251
253 """
254 Internal use for ROS-time routines.
255 @return: True if ROS is currently using wallclock time
256 @rtype: bool
257 """
258 return _rostime_current == None
259
272
274 """
275 Internal use.
276 Windows interrupts time.sleep with an IOError exception
277 when a signal is caught. Even when the signal is handled
278 by a callback, it will then proceed to throw IOError when
279 the handling has completed.
280
281 Refer to https://code.ros.org/trac/ros/ticket/3421.
282
283 So we create a platform dependant wrapper to handle this
284 here.
285 """
286 if sys.platform in ['win32']:
287 try:
288 time.sleep(duration)
289 except IOError:
290 pass
291 else:
292 time.sleep(duration)
293