39 from cStringIO
import StringIO
41 from io
import BytesIO
as StringIO
48 import cPickle
as pickle
57 rospy.rostime.set_rostime_initialized(
True)
61 import rospy.impl.simtime
65 rospy.rostime.switch_to_wallclock()
66 self.assertAlmostEqual(time.time(), rospy.get_time(), 1)
71 a = rospy.Time(random.randint(0, 10000), random.randint(0, 10000))
73 self.assertEqual(a.secs, b.secs)
74 self.assertEqual(a.nsecs, b.nsecs)
80 self.assertEqual(a.secs, c.secs)
81 self.assertEqual(a.nsecs, c.nsecs)
86 a = rospy.Duration(random.randint(0, 10000), random.randint(0, 10000))
88 self.assertEqual(a.secs, b.secs)
89 self.assertEqual(a.nsecs, b.nsecs)
95 self.assertEqual(a.secs, c.secs)
96 self.assertEqual(a.nsecs, c.nsecs)
100 from rospy
import Time, Duration
104 v = Duration.from_sec(0.1) > Time.from_sec(0.5)
107 self.assertFalse(failed,
"should have failed to compare")
109 v = Time.from_sec(0.4) > Duration.from_sec(0.1)
112 self.assertFalse(failed,
"should have failed to compare")
119 self.assertFalse(failed,
"negative time not allowed")
124 self.assertFalse(failed,
"negative time not allowed")
130 self.assertEqual(v.to_sec(), t)
132 self.assertEqual(Time.from_sec(0), Time())
133 self.assertEqual(Time.from_sec(1.), Time(1))
134 self.assertEqual(Time.from_sec(v.to_sec()), v)
135 self.assertEqual(v.from_sec(v.to_sec()), v)
138 self.assertEqual(v.to_sec(), v.to_time())
143 v = Time(1,0) + Time(1, 0)
146 self.assertFalse(failed,
"Time + Time must fail")
149 v = Time(1,0) + Duration(1, 0)
150 self.assertEqual(Time(2, 0), v)
151 v = Duration(1, 0) + Time(1,0)
152 self.assertEqual(Time(2, 0), v)
153 v = Time(1,1) + Duration(1, 1)
154 self.assertEqual(Time(2, 2), v)
155 v = Duration(1, 1) + Time(1,1)
156 self.assertEqual(Time(2, 2), v)
158 v = Time(1) + Duration(0, 1000000000)
159 self.assertEqual(Time(2), v)
160 v = Duration(1) + Time(0, 1000000000)
161 self.assertEqual(Time(2), v)
163 v = Time(100, 100) + Duration(300)
164 self.assertEqual(Time(400, 100), v)
165 v = Duration(300) + Time(100, 100)
166 self.assertEqual(Time(400, 100), v)
168 v = Time(100, 100) + Duration(300, 300)
169 self.assertEqual(Time(400, 400), v)
170 v = Duration(300, 300) + Time(100, 100)
171 self.assertEqual(Time(400, 400), v)
173 v = Time(100, 100) + Duration(300, -101)
174 self.assertEqual(Time(399, 999999999), v)
175 v = Duration(300, -101) + Time(100, 100)
176 self.assertEqual(Time(399, 999999999), v)
183 self.assertFalse(failed,
"Time - non Duration must fail")
184 class Foob(object):
pass
186 v = Time(1,0) - Foob()
189 self.assertFalse(failed,
"Time - non TVal must fail")
192 v = Time(1,0) - Duration(1, 0)
193 self.assertEqual(Time(), v)
195 v = Time(1,1) - Duration(-1, -1)
196 self.assertEqual(Time(2, 2), v)
197 v = Time(1) - Duration(0, 1000000000)
198 self.assertEqual(Time(), v)
199 v = Time(2) - Duration(0, 1000000000)
200 self.assertEqual(Time(1), v)
201 v = Time(400, 100) - Duration(300)
202 self.assertEqual(Time(100, 100), v)
203 v = Time(100, 100) - Duration(0, 101)
204 self.assertEqual(Time(99, 999999999), v)
207 v = Time(100, 100) - Time(100, 100)
208 self.assertEqual(Duration(), v)
209 v = Time(100, 100) - Time(100)
210 self.assertEqual(Duration(0,100), v)
211 v = Time(100) - Time(200)
212 self.assertEqual(Duration(-100), v)
215 Duration = rospy.Duration
219 self.assertEqual(v, Duration.from_sec(v.to_sec()))
220 self.assertEqual(v, v.from_sec(v.to_sec()))
222 self.assertEqual(v, Duration.from_sec(v.to_sec()))
223 self.assertEqual(v, v.from_sec(v.to_sec()))
227 self.assertEqual(-1, v.secs)
228 self.assertEqual(1, v.nsecs)
229 v = -Duration(-1, -1)
230 self.assertEqual(1, v.secs)
231 self.assertEqual(1, v.nsecs)
233 self.assertEqual(0, v.secs)
234 self.assertEqual(999999999, v.nsecs)
239 v = Duration(1,0) + Time(1, 0)
242 self.assertFalse(failed,
"Duration + Time must fail")
244 v = Duration(1,0) + 1
247 self.assertFalse(failed,
"Duration + int must fail")
249 v = Duration(1,0) + Duration(1, 0)
250 self.assertEqual(2, v.secs)
251 self.assertEqual(0, v.nsecs)
252 self.assertEqual(Duration(2, 0), v)
253 v = Duration(-1,-1) + Duration(1, 1)
254 self.assertEqual(0, v.secs)
255 self.assertEqual(0, v.nsecs)
256 self.assertEqual(Duration(), v)
257 v = Duration(1) + Duration(0, 1000000000)
258 self.assertEqual(2, v.secs)
259 self.assertEqual(0, v.nsecs)
260 self.assertEqual(Duration(2), v)
261 v = Duration(100, 100) + Duration(300)
262 self.assertEqual(Duration(400, 100), v)
263 v = Duration(100, 100) + Duration(300, 300)
264 self.assertEqual(Duration(400, 400), v)
265 v = Duration(100, 100) + Duration(300, -101)
266 self.assertEqual(Duration(399, 999999999), v)
270 v = Duration(1,0) - 1
273 self.assertFalse(failed,
"Duration - non duration must fail")
275 v = Duration(1, 0) - Time(1,0)
278 self.assertFalse(failed,
"Duration - Time must fail")
280 v = Duration(1,0) - Duration(1, 0)
281 self.assertEqual(Duration(), v)
282 v = Duration(-1,-1) - Duration(1, 1)
283 self.assertEqual(Duration(-3, 999999998), v)
284 v = Duration(1) - Duration(0, 1000000000)
285 self.assertEqual(Duration(), v)
286 v = Duration(2) - Duration(0, 1000000000)
287 self.assertEqual(Duration(1), v)
288 v = Duration(100, 100) - Duration(300)
289 self.assertEqual(Duration(-200, 100), v)
290 v = Duration(100, 100) - Duration(300, 101)
291 self.assertEqual(Duration(-201, 999999999), v)
294 self.assertEqual(abs(Duration()), Duration())
295 self.assertEqual(abs(Duration(1)), Duration(1))
296 self.assertEqual(abs(Duration(-1)), Duration(1))
297 self.assertEqual(abs(Duration(0,-1)), Duration(0,1))
298 self.assertEqual(abs(Duration(-1,-1)), Duration(1,1))
301 from rospy.rostime
import _set_rostime
302 from rospy
import Time
304 self.assertAlmostEqual(time.time(), rospy.get_time(), 1)
306 for t
in [Time.from_sec(1.0), Time.from_sec(4.0)]:
308 self.assertEqual(t, rospy.get_rostime())
309 self.assertEqual(t.to_time(), rospy.get_time())
312 rospy.rostime.switch_to_wallclock()
313 self.assertAlmostEqual(time.time(), rospy.get_time(), 1)
314 self.assertAlmostEqual(time.time(), rospy.get_rostime().to_time(), 1)
319 rospy.rostime.switch_to_wallclock()
321 rospy.sleep(rospy.Duration.from_sec(0.1))
323 from rospy.rostime
import _set_rostime
324 from rospy
import Time
326 t = Time.from_sec(1.0)
328 self.assertEqual(t, rospy.get_rostime())
329 self.assertEqual(t.to_time(), rospy.get_time())
334 self.assertFalse(test_sleep_done)
335 sleepthread = threading.Thread(target=sleeper, args=())
336 sleepthread.daemon =
True
339 self.assertFalse(test_sleep_done)
341 t = Time.from_sec(1000000.0)
344 self.assertTrue(test_sleep_done,
"sleeper did not wake up")
347 self.assertFalse(test_duration_sleep_done)
348 dursleepthread = threading.Thread(target=duration_sleeper, args=())
349 dursleepthread.daemon =
True
350 dursleepthread.start()
352 self.assertFalse(test_duration_sleep_done)
354 t = Time.from_sec(2000000.0)
357 self.assertTrue(test_sleep_done,
"sleeper did not wake up")
360 self.assertFalse(test_backwards_sleep_done)
361 backsleepthread = threading.Thread(target=backwards_sleeper, args=())
362 backsleepthread.daemon =
True
363 backsleepthread.start()
365 self.assertFalse(test_backwards_sleep_done)
367 t = Time.from_sec(1.0)
370 self.assertTrue(test_backwards_sleep_done,
"backwards sleeper was not given an exception")
372 test_duration_sleep_done =
False
374 global test_duration_sleep_done
375 rospy.sleep(rospy.Duration(10000.0))
376 test_duration_sleep_done =
True
378 test_sleep_done =
False
380 global test_sleep_done
382 test_sleep_done =
True
383 test_backwards_sleep_done =
False
385 global test_backwards_sleep_done
388 except rospy.ROSException:
389 test_backwards_sleep_done =
True