$search
00001 #!/usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('asmach_tutorials') 00004 import rospy 00005 import asmach as smach 00006 import smach_ros 00007 from asmach import async 00008 00009 # define state Foo 00010 class Foo(smach.State): 00011 def __init__(self): 00012 smach.State.__init__(self, outcomes=['outcome1','outcome2']) 00013 self.counter = 0 00014 00015 @async.function 00016 def execute_async(self, userdata): 00017 yield 00018 rospy.loginfo('Executing state FOO') 00019 if self.counter < 3: 00020 self.counter += 1 00021 async.returnValue('outcome1') 00022 else: 00023 async.returnValue('outcome2') 00024 00025 00026 # define state Bar 00027 class Bar(smach.State): 00028 def __init__(self): 00029 smach.State.__init__(self, outcomes=['outcome1']) 00030 00031 @async.function 00032 def execute_async(self, userdata): 00033 yield 00034 rospy.loginfo('Executing state BAR') 00035 async.returnValue('outcome1') 00036 00037 00038 00039 00040 00041 def main(): 00042 rospy.init_node('smach_example_state_machine') 00043 00044 # Create a SMACH state machine 00045 sm = smach.StateMachine(outcomes=['outcome4']) 00046 00047 # Open the container 00048 with sm: 00049 # Add states to the container 00050 smach.StateMachine.add('FOO', Foo(), 00051 transitions={'outcome1':'BAR', 'outcome2':'outcome4'}) 00052 smach.StateMachine.add('BAR', Bar(), 00053 transitions={'outcome1':'FOO'}) 00054 00055 # Execute SMACH plan 00056 outcome = smach.async.run(sm.execute_async()) 00057 00058 00059 00060 if __name__ == '__main__': 00061 main()