Go to the documentation of this file.00001
00002
00003 import rospy
00004 from flexbe_core import EventState
00005 from rospy.exceptions import ROSInterruptException
00006
00007 '''
00008 Created on 15.06.2013
00009
00010 @author: David Conner
00011 '''
00012
00013 class WaitState(EventState):
00014 '''
00015 Implements a state that can be used to wait on timed process.
00016
00017 -- wait_time float Amount of time to wait in seconds.
00018
00019 <= done Indicates that the wait time has elapsed.
00020
00021 '''
00022 def __init__(self, wait_time):
00023 '''Constructor'''
00024 super(WaitState, self).__init__(outcomes=['done'])
00025 self._wait = wait_time
00026
00027
00028 def execute(self, userdata):
00029 '''Execute this state'''
00030
00031 elapsed = rospy.get_rostime() - self._start_time;
00032 if (elapsed.to_sec() > self._wait):
00033 return 'done'
00034
00035
00036 def on_enter(self, userdata):
00037 '''Upon entering the state, save the current time and start waiting.'''
00038
00039 self._start_time = rospy.get_rostime()
00040
00041 try:
00042 self._rate.sleep()
00043 except ROSInterruptException:
00044 rospy.logwarn('Skipped sleep.')