wait_state.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 from flexbe_core import EventState
5 from rospy.exceptions import ROSInterruptException
6 
7 '''
8 Created on 15.06.2013
9 
10 @author: David Conner
11 '''
12 
13 class WaitState(EventState):
14  '''
15  Implements a state that can be used to wait on timed process.
16 
17  -- wait_time float Amount of time to wait in seconds.
18 
19  <= done Indicates that the wait time has elapsed.
20 
21  '''
22  def __init__(self, wait_time):
23  '''Constructor'''
24  super(WaitState, self).__init__(outcomes=['done'])
25  self._wait = wait_time
26 
27 
28  def execute(self, userdata):
29  '''Execute this state'''
30 
31  elapsed = rospy.get_rostime() - self._start_time;
32  if (elapsed.to_sec() > self._wait):
33  return 'done'
34 
35 
36  def on_enter(self, userdata):
37  '''Upon entering the state, save the current time and start waiting.'''
38 
39  self._start_time = rospy.get_rostime()
40 
41  try:
42  self._rate.sleep()
43  except ROSInterruptException:
44  rospy.logwarn('Skipped sleep.')
def on_enter(self, userdata)
Definition: wait_state.py:36
def execute(self, userdata)
Definition: wait_state.py:28
def __init__(self, wait_time)
Definition: wait_state.py:22


flexbe_states
Author(s): Philipp Schillinger
autogenerated on Wed Jun 5 2019 21:52:08