Home | Trees | Indices | Help |
|
---|
|
1 # Copyright (c) 2013-2015, Rethink Robotics 2 # All rights reserved. 3 # 4 # Redistribution and use in source and binary forms, with or without 5 # modification, are permitted provided that the following conditions are met: 6 # 7 # 1. Redistributions of source code must retain the above copyright notice, 8 # this list of conditions and the following disclaimer. 9 # 2. Redistributions in binary form must reproduce the above copyright 10 # notice, this list of conditions and the following disclaimer in the 11 # documentation and/or other materials provided with the distribution. 12 # 3. Neither the name of the Rethink Robotics nor the names of its 13 # contributors may be used to endorse or promote products derived from 14 # this software without specific prior written permission. 15 # 16 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 17 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 18 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 19 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 20 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 21 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 22 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 23 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 24 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 25 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 26 # POSSIBILITY OF SUCH DAMAGE. 27 28 import errno 29 30 import rospy 31 3233 -def wait_for(test, timeout=1.0, raise_on_error=True, rate=100, 34 timeout_msg="timeout expired", body=None):35 """ 36 Waits until some condition evaluates to true. 37 38 @param test: zero param function to be evaluated 39 @param timeout: max amount of time to wait. negative/inf for indefinitely 40 @param raise_on_error: raise or just return False 41 @param rate: the rate at which to check 42 @param timout_msg: message to supply to the timeout exception 43 @param body: optional function to execute while waiting 44 """ 45 end_time = rospy.get_time() + timeout 46 rate = rospy.Rate(rate) 47 notimeout = (timeout < 0.0) or timeout == float("inf") 48 while not test(): 49 if rospy.is_shutdown(): 50 if raise_on_error: 51 raise OSError(errno.ESHUTDOWN, "ROS Shutdown") 52 return False 53 elif (not notimeout) and (rospy.get_time() >= end_time): 54 if raise_on_error: 55 raise OSError(errno.ETIMEDOUT, timeout_msg) 56 return False 57 if callable(body): 58 body() 59 rate.sleep() 60 return True61
Home | Trees | Indices | Help |
|
---|
Generated by Epydoc 3.0.1 on Thu Aug 27 12:34:35 2015 | http://epydoc.sourceforge.net |