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