Package intera_dataflow :: Module wait_for'
[hide private]
[frames] | no frames]

Source Code for Module intera_dataflow.wait_for'

 1  # Copyright (c) 2013-2017, Rethink Robotics Inc. 
 2  # 
 3  # Licensed under the Apache License, Version 2.0 (the "License"); 
 4  # you may not use this file except in compliance with the License. 
 5  # You may obtain a copy of the License at 
 6  # 
 7  #     http://www.apache.org/licenses/LICENSE-2.0 
 8  # 
 9  # Unless required by applicable law or agreed to in writing, software 
10  # distributed under the License is distributed on an "AS IS" BASIS, 
11  # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 
12  # See the License for the specific language governing permissions and 
13  # limitations under the License. 
14   
15  import errno 
16   
17  import rospy 
18   
19   
20 -def wait_for(test, timeout=1.0, raise_on_error=True, rate=100, 21 timeout_msg="timeout expired", body=None):
22 """ 23 Waits until some condition evaluates to true. 24 25 @param test: zero param function to be evaluated 26 @param timeout: max amount of time to wait. negative/inf for indefinitely 27 @param raise_on_error: raise or just return False 28 @param rate: the rate at which to check 29 @param timout_msg: message to supply to the timeout exception 30 @param body: optional function to execute while waiting 31 """ 32 end_time = rospy.get_time() + timeout 33 rate = rospy.Rate(rate) 34 notimeout = (timeout < 0.0) or timeout == float("inf") 35 while not test(): 36 if rospy.is_shutdown(): 37 if raise_on_error: 38 raise OSError(errno.ESHUTDOWN, "ROS Shutdown") 39 return False 40 elif (not notimeout) and (rospy.get_time() >= end_time): 41 if raise_on_error: 42 raise OSError(errno.ETIMEDOUT, timeout_msg) 43 return False 44 if callable(body): 45 body() 46 rate.sleep() 47 return True
48