00001
00002 """
00003 Description:
00004 Spawn an actionlib action server, then create a state machine that sends
00005 some goals to the action server that will automatically succeed or abort.
00006 We expect the first goal to succeed, and the second goal to abort, so
00007 when the second goal aborts, we map that onto success of the state
00008 machine.
00009
00010 Usage:
00011 $> ./actionlib.py
00012
00013 Output:
00014 [INFO] : State machine starting in initial state 'GOAL_DEFAULT' with userdata:
00015 []
00016 [WARN] : Still waiting for action server 'test_action' to start... is it running?
00017 [INFO] : State machine transitioning 'GOAL_DEFAULT':'succeeded'-->'GOAL_STATIC'
00018 [INFO] : State machine terminating 'GOAL_STATIC':'aborted':'succeeded'
00019 """
00020
00021 import roslib; roslib.load_manifest('asmach_tutorials')
00022 import rospy
00023 import asmach as smach
00024 import smach_ros
00025
00026 from actionlib import *
00027 from actionlib.msg import *
00028
00029
00030 class TestServer:
00031 def __init__(self,name):
00032 self._sas = SimpleActionServer(name,
00033 TestAction,
00034 execute_cb=self.execute_cb)
00035
00036 def execute_cb(self, msg):
00037 if msg.goal == 0:
00038 self._sas.set_succeeded()
00039 elif msg.goal == 1:
00040 self._sas.set_aborted()
00041 elif msg.goal == 2:
00042 self._sas.set_preempted()
00043
00044 def main():
00045 rospy.init_node('smach_example_actionlib')
00046
00047
00048 server = TestServer('test_action')
00049
00050
00051 sm0 = smach.StateMachine(outcomes=['succeeded','aborted','preempted'])
00052
00053
00054 with sm0:
00055
00056
00057
00058
00059
00060
00061 smach.StateMachine.add('GOAL_DEFAULT',
00062 smach_ros.SimpleActionState('test_action', TestAction),
00063 {'succeeded':'GOAL_STATIC'})
00064
00065
00066
00067
00068 smach.StateMachine.add('GOAL_STATIC',
00069 smach_ros.SimpleActionState('test_action', TestAction,
00070 goal = TestGoal(goal=1)),
00071 {'aborted':'succeeded'})
00072
00073
00074
00075
00076
00077 outcome = sm0.execute()
00078
00079 rospy.signal_shutdown('All done.')
00080
00081 if __name__ == '__main__':
00082 main()