test_rospy_timer_online.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 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         # #2842 raising bounds from .01 to .03 for amazon VM 
00061 
00062         # make sure sleep is approximately right
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         # make sure sleep is approximately right
00069         self.assert_(abs(dur - 0.1) < 0.03, dur)
00070 
00071         # sleep for neg duration
00072         t = time.time()
00073         rospy.sleep(rospy.Duration.from_sec(-10.))
00074         dur = time.time() - t
00075         # make sure returned immediately
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         # make sure sleep is approximately right
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         # make sure we got an approximately correct number of callbacks
00111         self.assert_(abs(self.timer_callbacks - 10) < 2)
00112         # make sure error is approximately correct.  the Timer
00113         # implementation tracks error in accumulated real time.
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'])


test_rospy
Author(s): Ken Conley
autogenerated on Thu Jun 6 2019 21:10:57