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


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