$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 00008 # define state Foo 00009 class Foo(smach.State): 00010 def __init__(self): 00011 smach.State.__init__(self, 00012 outcomes=['outcome1','outcome2'], 00013 input_keys=['foo_counter_in'], 00014 output_keys=['foo_counter_out']) 00015 00016 def execute(self, userdata): 00017 rospy.loginfo('Executing state FOO') 00018 if userdata.foo_counter_in < 3: 00019 userdata.foo_counter_out = userdata.foo_counter_in + 1 00020 return 'outcome1' 00021 else: 00022 return 'outcome2' 00023 00024 00025 # define state Bar 00026 class Bar(smach.State): 00027 def __init__(self): 00028 smach.State.__init__(self, 00029 outcomes=['outcome1'], 00030 input_keys=['bar_counter_in']) 00031 00032 def execute(self, userdata): 00033 rospy.loginfo('Executing state BAR') 00034 rospy.loginfo('Counter = %f'%userdata.bar_counter_in) 00035 return '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 sm.userdata.sm_counter = 0 00047 00048 # Open the container 00049 with sm: 00050 # Add states to the container 00051 smach.StateMachine.add('FOO', Foo(), 00052 transitions={'outcome1':'BAR', 00053 'outcome2':'outcome4'}, 00054 remapping={'foo_counter_in':'sm_counter', 00055 'foo_counter_out':'sm_counter'}) 00056 smach.StateMachine.add('BAR', Bar(), 00057 transitions={'outcome1':'FOO'}, 00058 remapping={'bar_counter_in':'sm_counter'}) 00059 00060 00061 # Execute SMACH plan 00062 outcome = sm.execute() 00063 00064 00065 if __name__ == '__main__': 00066 main()