$search
00001 #!/usr/bin/env python 00002 """ 00003 Description: 00004 00005 Usage: 00006 $> roslaunch turtle_nodes.launch 00007 $> ./executive_step_02.py 00008 00009 Output: 00010 [INFO] : State machine starting in initial state 'RESET' with userdata: 00011 [] 00012 [INFO] : State machine transitioning 'RESET':'succeeded'-->'SPAWN' 00013 [INFO] : State machine terminating 'SPAWN':'succeeded':'succeeded' 00014 00015 """ 00016 00017 import roslib; roslib.load_manifest('smach_tutorials') 00018 import rospy 00019 00020 import threading 00021 00022 import smach 00023 from smach import StateMachine, ServiceState, SimpleActionState, IntrospectionServer 00024 00025 import std_srvs.srv 00026 import turtlesim.srv 00027 00028 def main(): 00029 rospy.init_node('smach_usecase_step_02') 00030 00031 # Create a SMACH state machine 00032 sm0 = StateMachine(outcomes=['succeeded','aborted','preempted']) 00033 00034 # Open the container 00035 with sm0: 00036 # Reset turtlesim 00037 StateMachine.add('RESET', 00038 ServiceState('reset', std_srvs.srv.Empty), 00039 {'succeeded':'SPAWN'}) 00040 00041 # Create a second turtle 00042 StateMachine.add('SPAWN', 00043 ServiceState('spawn', turtlesim.srv.Spawn, 00044 request = turtlesim.srv.SpawnRequest(0.0,0.0,0.0,'turtle2'))) 00045 00046 # Attach a SMACH introspection server 00047 sis = IntrospectionServer('smach_usecase_01', sm0, '/USE_CASE') 00048 sis.start() 00049 00050 # Execute SMACH tree 00051 outcome = sm0.execute() 00052 00053 # Signal ROS shutdown (kill threads in background) 00054 rospy.spin() 00055 00056 sis.stop() 00057 00058 if __name__ == '__main__': 00059 main()