00001
00002
00003 import roslib; roslib.load_manifest('asmach_tutorials')
00004 import rospy
00005 import asmach as smach
00006 import smach_ros
00007
00008
00009 class Foo(smach.State):
00010 def __init__(self):
00011 smach.State.__init__(self, outcomes=['outcome1','outcome2'])
00012 self.counter = 0
00013
00014 def execute(self, userdata):
00015 rospy.loginfo('Executing state FOO')
00016 if self.counter < 3:
00017 self.counter += 1
00018 return 'outcome1'
00019 else:
00020 return 'outcome2'
00021
00022
00023
00024 class Bar(smach.State):
00025 def __init__(self):
00026 smach.State.__init__(self, outcomes=['outcome2'])
00027
00028 def execute(self, userdata):
00029 rospy.loginfo('Executing state BAR')
00030 return 'outcome2'
00031
00032
00033
00034
00035
00036 def main():
00037 rospy.init_node('smach_example_state_machine')
00038
00039
00040 sm = smach.StateMachine(outcomes=['outcome4', 'outcome5'])
00041
00042
00043 with sm:
00044
00045 smach.StateMachine.add('FOO', Foo(),
00046 transitions={'outcome1':'BAR',
00047 'outcome2':'outcome4'})
00048 smach.StateMachine.add('BAR', Bar(),
00049 transitions={'outcome2':'FOO'})
00050
00051
00052 outcome = sm.execute()
00053
00054
00055 if __name__ == '__main__':
00056 main()