test_rospy_rostime.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 import os
00035 import sys
00036 import struct
00037 import unittest
00038 from cStringIO import StringIO
00039 import time
00040 import random
00041 
00042 import rospy.rostime
00043 
00044 # currently tests rospy.rostime, rospy.simtime, and some parts of rospy.client
00045 
00046 class TestRospyTime(unittest.TestCase):
00047     
00048     def setUp(self):
00049         rospy.rostime.set_rostime_initialized(True)
00050 
00051     def test_import_simtime(self):
00052         # trip wire test, make sure the module is loading
00053         import rospy.impl.simtime
00054         # can't actually do unit tests of simtime, requires rosunit
00055 
00056     def test_switch_to_wallclock(self):
00057         rospy.rostime.switch_to_wallclock()
00058         self.assertAlmostEqual(time.time(), rospy.get_time(), 1)
00059 
00060     def test_Time_get_setstate(self):
00061         # use deepcopy to test getstate/setstate
00062         import copy, random
00063         a = rospy.Time(random.randint(0, 10000), random.randint(0, 10000))
00064         b = copy.deepcopy(a)
00065         self.assertEquals(a.secs, b.secs)
00066         self.assertEquals(a.nsecs, b.nsecs)
00067 
00068         import cPickle, cStringIO
00069         buff = cStringIO.StringIO()
00070         cPickle.dump(a, buff)
00071         buff.seek(0)
00072         c = cPickle.load(buff)    
00073         self.assertEquals(a.secs, c.secs)
00074         self.assertEquals(a.nsecs, c.nsecs)
00075                                  
00076     def test_Duration_get_setstate(self):
00077         # use deepcopy to test getstate/setstate
00078         import copy, random
00079         a = rospy.Duration(random.randint(0, 10000), random.randint(0, 10000))
00080         b = copy.deepcopy(a)
00081         self.assertEquals(a.secs, b.secs)
00082         self.assertEquals(a.nsecs, b.nsecs)
00083 
00084         import cPickle, cStringIO
00085         buff = cStringIO.StringIO()
00086         cPickle.dump(a, buff)
00087         buff.seek(0)
00088         c = cPickle.load(buff)    
00089         self.assertEquals(a.secs, c.secs)
00090         self.assertEquals(a.nsecs, c.nsecs)
00091 
00092     def test_Time(self):
00093         # This is a copy of test_roslib_rostime
00094         from rospy import Time, Duration
00095         # #1600 Duration > Time should fail
00096         failed = False
00097         try:
00098             v = Duration.from_sec(0.1) > Time.from_sec(0.5)
00099             failed = True
00100         except: pass
00101         self.failIf(failed, "should have failed to compare")
00102         try:
00103             v = Time.from_sec(0.4) > Duration.from_sec(0.1)
00104             failed = True        
00105         except: pass
00106         self.failIf(failed, "should have failed to compare")
00107 
00108 
00109         try: # neg time fails
00110             Time(-1)
00111             failed = True
00112         except: pass
00113         self.failIf(failed, "negative time not allowed")
00114         try:
00115             Time(1, -1000000001)
00116             failed = True
00117         except: pass
00118         self.failIf(failed, "negative time not allowed")
00119 
00120         # test Time.now() is within 10 seconds of actual time (really generous)
00121         import time
00122         t = time.time()
00123         v = Time.from_sec(t)
00124         self.assertEquals(v.to_sec(), t)
00125         # test from_sec()
00126         self.assertEquals(Time.from_sec(0), Time())
00127         self.assertEquals(Time.from_sec(1.), Time(1))
00128         self.assertEquals(Time.from_sec(v.to_sec()), v)
00129         self.assertEquals(v.from_sec(v.to_sec()), v)
00130 
00131         # test to_time()
00132         self.assertEquals(v.to_sec(), v.to_time())
00133 
00134         # test addition
00135         # - time + time fails
00136         try:
00137             v = Time(1,0) + Time(1, 0)
00138             failed = True
00139         except: pass
00140         self.failIf(failed, "Time + Time must fail")
00141 
00142         # - time + duration
00143         v = Time(1,0) + Duration(1, 0)
00144         self.assertEquals(Time(2, 0), v)
00145         v = Duration(1, 0) + Time(1,0)
00146         self.assertEquals(Time(2, 0), v)
00147         v = Time(1,1) + Duration(1, 1)
00148         self.assertEquals(Time(2, 2), v)
00149         v = Duration(1, 1) + Time(1,1)
00150         self.assertEquals(Time(2, 2), v)
00151 
00152         v = Time(1) + Duration(0, 1000000000)
00153         self.assertEquals(Time(2), v)
00154         v = Duration(1) + Time(0, 1000000000)
00155         self.assertEquals(Time(2), v)
00156 
00157         v = Time(100, 100) + Duration(300)
00158         self.assertEquals(Time(400, 100), v)
00159         v = Duration(300) + Time(100, 100)
00160         self.assertEquals(Time(400, 100), v)
00161 
00162         v = Time(100, 100) + Duration(300, 300)
00163         self.assertEquals(Time(400, 400), v)
00164         v = Duration(300, 300) + Time(100, 100)
00165         self.assertEquals(Time(400, 400), v)
00166 
00167         v = Time(100, 100) + Duration(300, -101)
00168         self.assertEquals(Time(399, 999999999), v)
00169         v =  Duration(300, -101) + Time(100, 100)
00170         self.assertEquals(Time(399, 999999999), v)
00171 
00172         # test subtraction
00173         try:
00174             v = Time(1,0) - 1
00175             failed = True
00176         except: pass
00177         self.failIf(failed, "Time - non Duration must fail")
00178         class Foob(object): pass      
00179         try:
00180             v = Time(1,0) - Foob()
00181             failed = True          
00182         except: pass
00183         self.failIf(failed, "Time - non TVal must fail")
00184 
00185         # - Time - Duration
00186         v = Time(1,0) - Duration(1, 0)
00187         self.assertEquals(Time(), v)
00188 
00189         v = Time(1,1) - Duration(-1, -1)
00190         self.assertEquals(Time(2, 2), v)
00191         v = Time(1) - Duration(0, 1000000000)
00192         self.assertEquals(Time(), v)
00193         v = Time(2) - Duration(0, 1000000000)
00194         self.assertEquals(Time(1), v)
00195         v = Time(400, 100) - Duration(300)
00196         self.assertEquals(Time(100, 100), v)
00197         v = Time(100, 100) - Duration(0, 101)
00198         self.assertEquals(Time(99, 999999999), v)
00199 
00200         # - Time - Time = Duration      
00201         v = Time(100, 100) - Time(100, 100)
00202         self.assertEquals(Duration(), v)
00203         v = Time(100, 100) - Time(100)
00204         self.assertEquals(Duration(0,100), v)
00205         v = Time(100) - Time(200)
00206         self.assertEquals(Duration(-100), v)
00207 
00208     def test_Duration(self):
00209         Duration = rospy.Duration
00210 
00211         # test from_sec
00212         v = Duration(1000)
00213         self.assertEquals(v, Duration.from_sec(v.to_sec()))
00214         self.assertEquals(v, v.from_sec(v.to_sec()))
00215         v = Duration(0,1000)
00216         self.assertEquals(v, Duration.from_sec(v.to_sec()))
00217         self.assertEquals(v, v.from_sec(v.to_sec()))
00218       
00219         # test neg
00220         v = -Duration(1, -1)
00221         self.assertEquals(-1, v.secs)
00222         self.assertEquals(1, v.nsecs)
00223         v = -Duration(-1, -1)
00224         self.assertEquals(1, v.secs)
00225         self.assertEquals(1, v.nsecs)
00226         v = -Duration(-1, 1)
00227         self.assertEquals(0, v.secs)
00228         self.assertEquals(999999999, v.nsecs)
00229       
00230         # test addition
00231         failed = False
00232         try:
00233             v = Duration(1,0) + Time(1, 0)
00234             failed = True
00235         except: pass
00236         self.failIf(failed, "Duration + Time must fail")
00237         try:
00238             v = Duration(1,0) + 1
00239             failed = True
00240         except: pass
00241         self.failIf(failed, "Duration + int must fail")
00242           
00243         v = Duration(1,0) + Duration(1, 0)
00244         self.assertEquals(2, v.secs)
00245         self.assertEquals(0, v.nsecs)
00246         self.assertEquals(Duration(2, 0), v)
00247         v = Duration(-1,-1) + Duration(1, 1)
00248         self.assertEquals(0, v.secs)
00249         self.assertEquals(0, v.nsecs)
00250         self.assertEquals(Duration(), v)
00251         v = Duration(1) + Duration(0, 1000000000)
00252         self.assertEquals(2, v.secs)
00253         self.assertEquals(0, v.nsecs)
00254         self.assertEquals(Duration(2), v)
00255         v = Duration(100, 100) + Duration(300)
00256         self.assertEquals(Duration(400, 100), v)
00257         v = Duration(100, 100) + Duration(300, 300)
00258         self.assertEquals(Duration(400, 400), v)
00259         v = Duration(100, 100) + Duration(300, -101)
00260         self.assertEquals(Duration(399, 999999999), v)
00261         
00262         # test subtraction
00263         try:
00264             v = Duration(1,0) - 1
00265             failed = True
00266         except: pass
00267         self.failIf(failed, "Duration - non duration must fail")
00268         try:
00269             v = Duration(1, 0) - Time(1,0)
00270             failed = True          
00271         except: pass
00272         self.failIf(failed, "Duration - Time must fail")
00273         
00274         v = Duration(1,0) - Duration(1, 0)
00275         self.assertEquals(Duration(), v)
00276         v = Duration(-1,-1) - Duration(1, 1)
00277         self.assertEquals(Duration(-3, 999999998), v)
00278         v = Duration(1) - Duration(0, 1000000000)
00279         self.assertEquals(Duration(), v)
00280         v = Duration(2) - Duration(0, 1000000000)
00281         self.assertEquals(Duration(1), v)
00282         v = Duration(100, 100) - Duration(300)
00283         self.assertEquals(Duration(-200, 100), v)
00284         v = Duration(100, 100) - Duration(300, 101)
00285         self.assertEquals(Duration(-201, 999999999), v)
00286 
00287         # test abs
00288         self.assertEquals(abs(Duration()), Duration())
00289         self.assertEquals(abs(Duration(1)), Duration(1))      
00290         self.assertEquals(abs(Duration(-1)), Duration(1))
00291         self.assertEquals(abs(Duration(0,-1)), Duration(0,1))
00292         self.assertEquals(abs(Duration(-1,-1)), Duration(1,1))
00293       
00294     def test_set_rostime(self):
00295         from rospy.rostime import _set_rostime
00296         from rospy import Time 
00297 
00298         self.assertAlmostEqual(time.time(), rospy.get_time(), 1)
00299 
00300         for t in [Time.from_sec(1.0), Time.from_sec(4.0)]:
00301             _set_rostime(t)
00302             self.assertEquals(t, rospy.get_rostime())
00303             self.assertEquals(t.to_time(), rospy.get_time())        
00304 
00305     def test_get_rostime(self):
00306         rospy.rostime.switch_to_wallclock()
00307         self.assertAlmostEqual(time.time(), rospy.get_time(), 1)
00308         self.assertAlmostEqual(time.time(), rospy.get_rostime().to_time(), 1)
00309         #rest of get_rostime implicitly tested by update_rostime tests
00310 
00311     def test_sleep(self):
00312         # test wallclock sleep
00313         rospy.rostime.switch_to_wallclock()
00314         rospy.sleep(0.1)
00315         rospy.sleep(rospy.Duration.from_sec(0.1))
00316         
00317         from rospy.rostime import _set_rostime
00318         from rospy import Time 
00319 
00320         t = Time.from_sec(1.0)
00321         _set_rostime(t)
00322         self.assertEquals(t, rospy.get_rostime())
00323         self.assertEquals(t.to_time(), rospy.get_time())        
00324 
00325         import thread
00326 
00327         #start sleeper
00328         self.failIf(test_sleep_done)
00329         thread.start_new_thread(sleeper, ())
00330         time.sleep(1.0) #make sure thread is spun up
00331         self.failIf(test_sleep_done)
00332 
00333         t = Time.from_sec(1000000.0)
00334         _set_rostime(t)
00335         time.sleep(0.5) #give sleeper time to wakeup
00336         self.assert_(test_sleep_done, "sleeper did not wake up")
00337 
00338         #start duration sleeper
00339         self.failIf(test_duration_sleep_done)                
00340         thread.start_new_thread(duration_sleeper, ())
00341         time.sleep(1.0) #make sure thread is spun up
00342         self.failIf(test_duration_sleep_done)
00343 
00344         t = Time.from_sec(2000000.0)
00345         _set_rostime(t)
00346         time.sleep(0.5) #give sleeper time to wakeup
00347         self.assert_(test_sleep_done, "sleeper did not wake up")
00348 
00349         #start backwards sleeper
00350         self.failIf(test_backwards_sleep_done)
00351         thread.start_new_thread(backwards_sleeper, ())
00352         time.sleep(1.0) #make sure thread is spun up
00353         self.failIf(test_backwards_sleep_done)
00354 
00355         t = Time.from_sec(1.0)
00356         _set_rostime(t)
00357         time.sleep(0.5) #give sleeper time to wakeup
00358         self.assert_(test_backwards_sleep_done, "backwards sleeper was not given an exception")
00359     
00360 test_duration_sleep_done = False
00361 def duration_sleeper():
00362     global test_duration_sleep_done
00363     rospy.sleep(rospy.Duration(10000.0))
00364     test_duration_sleep_done = True
00365 
00366 test_sleep_done = False
00367 def sleeper():
00368     global test_sleep_done
00369     rospy.sleep(10000.0)
00370     test_sleep_done = True
00371 test_backwards_sleep_done = False    
00372 def backwards_sleeper():
00373     global test_backwards_sleep_done
00374     try:
00375         rospy.sleep(10000.0)
00376     except rospy.ROSException:
00377         test_backwards_sleep_done = True


test_rospy
Author(s): Ken Conley
autogenerated on Mon Oct 6 2014 11:47:19