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 from __future__ import print_function
00035
00036 import os
00037 import sys
00038 import unittest
00039 import time
00040
00041 import rosunit
00042
00043 from threading import Thread
00044
00045 class TestRospyTimerOnline(unittest.TestCase):
00046
00047 def __init__(self, *args):
00048 unittest.TestCase.__init__(self, *args)
00049 import rospy
00050 rospy.init_node('test_rospy_timer_online')
00051 self.timer_callbacks = 0
00052 self.timer_event = None
00053
00054 def test_sleep(self):
00055 import rospy
00056 import time
00057 t = time.time()
00058 rospy.sleep(0.1)
00059 dur = time.time() - t
00060
00061
00062
00063 self.assert_(abs(dur - 0.1) < 0.03, dur)
00064
00065 t = time.time()
00066 rospy.sleep(rospy.Duration.from_sec(0.1))
00067 dur = time.time() - t
00068
00069 self.assert_(abs(dur - 0.1) < 0.03, dur)
00070
00071
00072 t = time.time()
00073 rospy.sleep(rospy.Duration.from_sec(-10.))
00074 dur = time.time() - t
00075
00076 self.assert_(abs(dur) < 0.1, dur)
00077
00078 def test_Rate(self):
00079 import rospy
00080 import time
00081 t = time.time()
00082 count = 0
00083 r = rospy.Rate(10)
00084 for x in range(10):
00085 r.sleep()
00086 dur = time.time() - t
00087
00088 self.assert_(abs(dur - 1.0) < 0.5, dur)
00089
00090 def _Timer_callback(self, event):
00091 self.timer_callbacks += 1
00092 self.timer_event = event
00093
00094 def callback(event):
00095 print('last_expected: ', event.last_expected)
00096 print('last_real: ', event.last_real)
00097 print('current_expected: ', event.current_expected)
00098 print('current_real: ', event.current_real)
00099 print('current_error: ', (event.current_real - event.current_expected).to_sec())
00100 print('profile.last_duration:', event.last_duration)
00101 if event.last_real:
00102 print('last_error: ', (event.last_real - event.last_expected).to_sec(), 'secs')
00103
00104 def test_Timer(self):
00105 import rospy
00106 timer = rospy.Timer(rospy.Duration(1), self._Timer_callback)
00107 time.sleep(10)
00108 timer.shutdown()
00109
00110
00111 self.assert_(abs(self.timer_callbacks - 10) < 2)
00112
00113
00114 ev = self.timer_event
00115 self.assert_(ev is not None)
00116 self.assert_(abs((ev.current_real - ev.current_expected).to_sec()) < 2.)
00117
00118 if __name__ == '__main__':
00119 rosunit.unitrun('test_rospy', sys.argv[0], TestRospyTimerOnline, coverage_packages=['rospy.timer'])