00001
00002 """
00003 Description:
00004 Create a simple 3-state state machine.
00005
00006 Usage:
00007 $> ./state_machine.py
00008
00009 Output:
00010 [INFO] : State machine starting in initial state 'FOO' with userdata:
00011 []
00012 [INFO] : State machine transitioning 'FOO':'done'-->'BAR'
00013 [INFO] : State machine transitioning 'BAR':'done'-->'BAZ'
00014 [INFO] : State machine terminating 'BAZ':'done':'succeeded'
00015
00016 """
00017
00018 import roslib; roslib.load_manifest('asmach_tutorials')
00019 import rospy
00020 import asmach as smach
00021 from asmach import async
00022 import smach_ros
00023
00024 class ExampleState(smach.State):
00025 def __init__(self):
00026 smach.State.__init__(self, outcomes = ['done'])
00027
00028 @async.function
00029 def execute_async(self, ud):
00030 yield
00031 async.returnValue('done')
00032
00033 def main():
00034 rospy.init_node('smach_example_state_machine')
00035
00036
00037 sm = smach.StateMachine(outcomes=['succeeded','aborted'])
00038
00039
00040 with sm:
00041
00042 smach.StateMachine.add('FOO', ExampleState(), {'done':'BAR'})
00043 smach.StateMachine.add('BAR', ExampleState(), {'done':'BAZ'})
00044 smach.StateMachine.add('BAZ',
00045 ExampleState(),
00046 {'done':'succeeded'})
00047
00048
00049 outcome = smach.async.run(sm.execute_async())
00050
00051 if __name__ == '__main__':
00052 main()