diff --git a/smach_tutorials/CMakeLists.txt b/smach_tutorials/CMakeLists.txt new file mode 100644 index 0000000..8ffbcfc --- /dev/null +++ b/smach_tutorials/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 2.8.3) +project(smach_tutorials) + +find_package(catkin REQUIRED COMPONENTS actionlib_msgs message_generation) + +add_action_files( + DIRECTORY action + FILES Test.action) +generate_messages(DEPENDENCIES actionlib_msgs) + +catkin_package(CATKIN_DEPENDS actionlib_msgs message_runtime) + +install( + DIRECTORY examples scripts + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + USE_SOURCE_PERMISSIONS + FILES_MATCHING PATTERN "*.py" +) diff --git a/smach_tutorials/action/Test.action b/smach_tutorials/action/Test.action new file mode 100644 index 0000000..fb8b0ac --- /dev/null +++ b/smach_tutorials/action/Test.action @@ -0,0 +1,3 @@ +float64 goal +--- +--- diff --git a/smach_tutorials/examples/actionlib2_test.py b/smach_tutorials/examples/actionlib2_test.py new file mode 100755 index 0000000..8a70ef6 --- /dev/null +++ b/smach_tutorials/examples/actionlib2_test.py @@ -0,0 +1,80 @@ +#!/usr/bin/env python + +import rospy +import smach +import smach_ros + +from smach_tutorials.msg import TestAction, TestGoal +from actionlib import * +from actionlib_msgs.msg import * + + +# Create a trivial action server +class TestServer: + def __init__(self,name): + self._sas = SimpleActionServer(name, + TestAction, + execute_cb=self.execute_cb) + + def execute_cb(self, msg): + if msg.goal == 0: + self._sas.set_succeeded() + elif msg.goal == 1: + self._sas.set_aborted() + elif msg.goal == 2: + self._sas.set_preempted() + +def main(): + rospy.init_node('smach_example_actionlib') + + # Start an action server + server = TestServer('test_action') + + # Create a SMACH state machine + sm0 = smach.StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Add states to the container + + # Add a simple action state. This will use an empty, default goal + # As seen in TestServer above, an empty goal will always return with + # GoalStatus.SUCCEEDED, causing this simple action state to return + # the outcome 'succeeded' + smach.StateMachine.add('GOAL_DEFAULT', + smach_ros.SimpleActionState('test_action', TestAction), + {'succeeded':'GOAL_STATIC'}) + + # Add another simple action state. This will give a goal + # that should abort the action state when it is received, so we + # map 'aborted' for this state onto 'succeeded' for the state machine. + smach.StateMachine.add('GOAL_STATIC', + smach_ros.SimpleActionState('test_action', TestAction, + goal = TestGoal(goal=1)), + {'aborted':'GOAL_CB'}) + + + # Add another simple action state. This will give a goal + # that should abort the action state when it is received, so we + # map 'aborted' for this state onto 'succeeded' for the state machine. + def goal_callback(userdata, default_goal): + goal = TestGoal() + goal.goal = 2 + return goal + + smach.StateMachine.add('GOAL_CB', + smach_ros.SimpleActionState('test_action', TestAction, + goal_cb = goal_callback), + {'aborted':'succeeded'}) + + # For more examples on how to set goals and process results, see + # executive_smach/smach_ros/tests/smach_actionlib.py + + # Execute SMACH plan + outcome = sm0.execute() + + rospy.signal_shutdown('All done.') + + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/actionlib_test.py b/smach_tutorials/examples/actionlib_test.py new file mode 100755 index 0000000..d476de1 --- /dev/null +++ b/smach_tutorials/examples/actionlib_test.py @@ -0,0 +1,82 @@ +#!/usr/bin/env python +""" +Description: + Spawn an actionlib action server, then create a state machine that sends + some goals to the action server that will automatically succeed or abort. + We expect the first goal to succeed, and the second goal to abort, so + when the second goal aborts, we map that onto success of the state + machine. + +Usage: + $> ./actionlib.py + +Output: + [INFO] : State machine starting in initial state 'GOAL_DEFAULT' with userdata: + [] + [WARN] : Still waiting for action server 'test_action' to start... is it running? + [INFO] : State machine transitioning 'GOAL_DEFAULT':'succeeded'-->'GOAL_STATIC' + [INFO] : State machine terminating 'GOAL_STATIC':'aborted':'succeeded' +""" + +import rospy +import smach +import smach_ros + +from smach_tutorials.msg import TestAction, TestGoal +from actionlib import * +from actionlib_msgs.msg import * + +# Create a trivial action server +class TestServer: + def __init__(self,name): + self._sas = SimpleActionServer(name, + TestAction, + execute_cb=self.execute_cb) + + def execute_cb(self, msg): + if msg.goal == 0: + self._sas.set_succeeded() + elif msg.goal == 1: + self._sas.set_aborted() + elif msg.goal == 2: + self._sas.set_preempted() + +def main(): + rospy.init_node('smach_example_actionlib') + + # Start an action server + server = TestServer('test_action') + + # Create a SMACH state machine + sm0 = smach.StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Add states to the container + + # Add a simple action sttate. This will use an emtpy, default goal + # As seen in TestServer above, an empty goal will always return with + # GoalStatus.SUCCEEDED, causing this simple action state to return + # the outcome 'succeeded' + smach.StateMachine.add('GOAL_DEFAULT', + smach_ros.SimpleActionState('test_action', TestAction), + {'succeeded':'GOAL_STATIC'}) + + # Add another simple action state. This will give a goal + # that should abort the action state when it is received, so we + # map 'aborted' for this state onto 'succeeded' for the state machine. + smach.StateMachine.add('GOAL_STATIC', + smach_ros.SimpleActionState('test_action', TestAction, + goal = TestGoal(goal=1)), + {'aborted':'succeeded'}) + + # For more examples on how to set goals and process results, see + # executive_python/smach/tests/smach_actionlib.py + + # Execute SMACH plan + outcome = sm0.execute() + + rospy.signal_shutdown('All done.') + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/concurrence.py b/smach_tutorials/examples/concurrence.py new file mode 100755 index 0000000..3462445 --- /dev/null +++ b/smach_tutorials/examples/concurrence.py @@ -0,0 +1,74 @@ +#!/usr/bin/env python +""" +Description: + This creates a concurrence with two states, one state, 'SET', waits three + seconds before setting something in userdata, while another state 'GET' + blocks while checking for thie userdata key, and only returns once it + has been set. + +Usage: + $> ./concurrence.py + +Output: + [INFO] 1279226335.169182: Concurrence starting with userdata: + [] + [INFO] : >>> Waiting for data... + [INFO] : >>> Waiting for data... + [INFO] : >>> Waiting for data... + [INFO] : >>> Waiting for data... + [INFO] : >>> Waiting for data... + [INFO] : >>> Waiting for data... + [INFO] : >>> Set data: hello + [INFO] : >>> GOT DATA! x = hello + [INFO] : Concurrent Outcomes: {'SET': 'set_it', 'GET': 'got_it'} +""" + +import rospy +import smach +import smach_ros + +# Define a state to set some user data +class Setter(smach.State): + def __init__(self, val): + smach.State.__init__(self, outcomes = ['set_it'], output_keys = ['x']) + self._val = val + def execute(self, ud): + # Delay a bit to make this clear + rospy.sleep(3.0) + # Set the data + ud.x = self._val + rospy.loginfo('>>> Set data: %s' % str(self._val)) + return 'set_it' + +# Define a state to get some user data +class Getter(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes = ['got_it'], input_keys = ['x']) + def execute(self, ud): + # Wait for data to appear + while 'x' not in ud: + rospy.loginfo('>>> Waiting for data...') + rospy.sleep(0.5) + rospy.loginfo('>>> GOT DATA! x = '+str(ud.x)) + return 'got_it' + +def main(): + rospy.init_node('smach_example_concurrence') + + # Create a SMACH state machine + cc0 = smach.Concurrence( + outcomes=['succeeded', 'aborted'], + default_outcome='aborted', + outcome_map = {'succeeded':{'SET':'set_it','GET':'got_it'}}) + + # Open the container + with cc0: + # Add states to the container + smach.Concurrence.add('SET', Setter(val='hello')) + smach.Concurrence.add('GET', Getter()) + + # Execute SMACH plan + outcome = cc0.execute() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/concurrence2.py b/smach_tutorials/examples/concurrence2.py new file mode 100755 index 0000000..bcf1243 --- /dev/null +++ b/smach_tutorials/examples/concurrence2.py @@ -0,0 +1,79 @@ +#!/usr/bin/env python + +import rospy +import smach +import smach_ros + +# define state Foo +class Foo(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1','outcome2']) + self.counter = 0 + + def execute(self, userdata): + rospy.loginfo('Executing state FOO') + if self.counter < 3: + self.counter += 1 + return 'outcome1' + else: + return 'outcome2' + + +# define state Bar +class Bar(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAR') + return 'outcome1' + + + +# define state Bas +class Bas(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome3']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAS') + return 'outcome3' + + + + +def main(): + rospy.init_node('smach_example_state_machine') + + # Create the top level SMACH state machine + sm_top = smach.StateMachine(outcomes=['outcome6']) + + # Open the container + with sm_top: + + smach.StateMachine.add('BAS', Bas(), + transitions={'outcome3':'CON'}) + + # Create the sub SMACH state machine + sm_con = smach.Concurrence(outcomes=['outcome4','outcome5'], + default_outcome='outcome4', + outcome_map={'outcome5': + { 'FOO':'outcome2', + 'BAR':'outcome1'}}) + + # Open the container + with sm_con: + # Add states to the container + smach.Concurrence.add('FOO', Foo()) + smach.Concurrence.add('BAR', Bar()) + + smach.StateMachine.add('CON', sm_con, + transitions={'outcome4':'CON', + 'outcome5':'outcome6'}) + + # Execute SMACH plan + outcome = sm_top.execute() + + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/iterator_tutorial.py b/smach_tutorials/examples/iterator_tutorial.py new file mode 100755 index 0000000..6b4de06 --- /dev/null +++ b/smach_tutorials/examples/iterator_tutorial.py @@ -0,0 +1,88 @@ +#! /usr/bin/env python +## %Tag(FULLTEXT)% + + +import roslib; roslib.load_manifest('smach') +roslib.load_manifest('smach_ros') +import rospy + +import smach +from smach import Iterator, StateMachine, CBState +from smach_ros import ConditionState, IntrospectionServer + +def construct_sm(): + sm = StateMachine(outcomes = ['succeeded','aborted','preempted']) + sm.userdata.nums = range(25, 88, 3) + sm.userdata.even_nums = [] + sm.userdata.odd_nums = [] + with sm: +## %Tag(ITERATOR)% + tutorial_it = Iterator(outcomes = ['succeeded','preempted','aborted'], + input_keys = ['nums', 'even_nums', 'odd_nums'], + it = lambda: range(0, len(sm.userdata.nums)), + output_keys = ['even_nums', 'odd_nums'], + it_label = 'index', + exhausted_outcome = 'succeeded') +## %EndTag(ITERATOR)% +## %Tag(CONTAINER)% + with tutorial_it: + container_sm = StateMachine(outcomes = ['succeeded','preempted','aborted','continue'], + input_keys = ['nums', 'index', 'even_nums', 'odd_nums'], + output_keys = ['even_nums', 'odd_nums']) + with container_sm: + #test wether even or odd + StateMachine.add('EVEN_OR_ODD', + ConditionState(cond_cb = lambda ud:ud.nums[ud.index]%2, + input_keys=['nums', 'index']), + {'true':'ODD', + 'false':'EVEN' }) + #add even state + @smach.cb_interface(input_keys=['nums', 'index', 'even_nums'], + output_keys=['odd_nums'], + outcomes=['succeeded']) + def even_cb(ud): + ud.even_nums.append(ud.nums[ud.index]) + return 'succeeded' + StateMachine.add('EVEN', CBState(even_cb), + {'succeeded':'continue'}) + #add odd state + @smach.cb_interface(input_keys=['nums', 'index', 'odd_nums'], + output_keys=['odd_nums'], + outcomes=['succeeded']) + def odd_cb(ud): + ud.odd_nums.append(ud.nums[ud.index]) + return 'succeeded' + StateMachine.add('ODD', CBState(odd_cb), + {'succeeded':'continue'}) +## %EndTag(CONTAINER)% +## %Tag(ADDCONTAINER)% + #close container_sm + Iterator.set_contained_state('CONTAINER_STATE', + container_sm, + loop_outcomes=['continue']) +## %EndTag(ADDCONTAINER)% +## %Tag(ADDITERATOR)% + #close the tutorial_it + StateMachine.add('TUTORIAL_IT',tutorial_it, + {'succeeded':'succeeded', + 'aborted':'aborted'}) +## %EndTag(ADDITERATOR)% + return sm + +def main(): + rospy.init_node("iterator_tutorial") + sm_iterator = construct_sm() + + # Run state machine introspection server for smach viewer + intro_server = IntrospectionServer('iterator_tutorial',sm_iterator,'/ITERATOR_TUTORIAL') + intro_server.start() + + + outcome = sm_iterator.execute() + + rospy.spin() + intro_server.stop() + +if __name__ == "__main__": + main() +## %EndTag(FULLTEXT)% diff --git a/smach_tutorials/examples/sequence.py b/smach_tutorials/examples/sequence.py new file mode 100755 index 0000000..0e73589 --- /dev/null +++ b/smach_tutorials/examples/sequence.py @@ -0,0 +1,49 @@ +#!/usr/bin/env python +""" +Description: + Create a simple 3-state state sequence. A Sequence is a StateMachine + that just assumes that states added in some sequence should be + executed in the order in which they were added, but only if they + return the "connector outcome" given in the Sequence constructor. + +Usage: + $> ./sequence.py + +Output: + [INFO] : State machine starting in initial state 'FOO' with userdata: + [] + [INFO] : State machine transitioning 'FOO':'done'-->'BAR' + [INFO] : State machine transitioning 'BAR':'done'-->'BAZ' + [INFO] : State machine terminating 'BAZ':'done':'succeeded' +""" + +import rospy +import smach +import smach_ros + +class ExampleState(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes = ['done']) + def execute(self, ud): + return 'done' + +def main(): + rospy.init_node('smach_example_sequence') + + # Create a SMACH state machine + sq = smach.Sequence( + outcomes = ['succeeded'], + connector_outcome = 'done') + + # Open the container + with sq: + # Add states to the container + smach.Sequence.add('FOO', ExampleState()) + smach.Sequence.add('BAR', ExampleState()) + smach.Sequence.add('BAZ', ExampleState(), {'done':'succeeded'}) + + # Execute SMACH plan + outcome = sq.execute() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/state_machine.py b/smach_tutorials/examples/state_machine.py new file mode 100755 index 0000000..d5afc95 --- /dev/null +++ b/smach_tutorials/examples/state_machine.py @@ -0,0 +1,47 @@ +#!/usr/bin/env python +""" +Description: + Create a simple 3-state state machine. + +Usage: + $> ./state_machine.py + +Output: + [INFO] : State machine starting in initial state 'FOO' with userdata: + [] + [INFO] : State machine transitioning 'FOO':'done'-->'BAR' + [INFO] : State machine transitioning 'BAR':'done'-->'BAZ' + [INFO] : State machine terminating 'BAZ':'done':'succeeded' + +""" + +import rospy +import smach +import smach_ros + +class ExampleState(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes = ['done']) + def execute(self, ud): + return 'done' + +def main(): + rospy.init_node('smach_example_state_machine') + + # Create a SMACH state machine + sm = smach.StateMachine(outcomes=['succeeded','aborted']) + + # Open the container + with sm: + # Add states to the container + smach.StateMachine.add('FOO', ExampleState(), {'done':'BAR'}) + smach.StateMachine.add('BAR', ExampleState(), {'done':'BAZ'}) + smach.StateMachine.add('BAZ', + ExampleState(), + {'done':'succeeded'}) + + # Execute SMACH plan + outcome = sm.execute() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/state_machine2.py b/smach_tutorials/examples/state_machine2.py new file mode 100755 index 0000000..c14d4d7 --- /dev/null +++ b/smach_tutorials/examples/state_machine2.py @@ -0,0 +1,56 @@ +#!/usr/bin/env python + +import roslib; roslib.load_manifest('smach_tutorials') +import rospy +import smach +import smach_ros + +# define state Foo +class Foo(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1','outcome2']) + self.counter = 0 + + def execute(self, userdata): + rospy.loginfo('Executing state FOO') + if self.counter < 3: + self.counter += 1 + return 'outcome1' + else: + return 'outcome2' + + +# define state Bar +class Bar(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAR') + return 'outcome1' + + + + + +def main(): + rospy.init_node('smach_example_state_machine') + + # Create a SMACH state machine + sm = smach.StateMachine(outcomes=['outcome4']) + + # Open the container + with sm: + # Add states to the container + smach.StateMachine.add('FOO', Foo(), + transitions={'outcome1':'BAR', 'outcome2':'outcome4'}) + smach.StateMachine.add('BAR', Bar(), + transitions={'outcome1':'FOO'}) + + # Execute SMACH plan + outcome = sm.execute() + + + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/state_machine_nesting.py b/smach_tutorials/examples/state_machine_nesting.py new file mode 100755 index 0000000..55d41a0 --- /dev/null +++ b/smach_tutorials/examples/state_machine_nesting.py @@ -0,0 +1,71 @@ +#!/usr/bin/env python +""" +Description: + Create one state machine, put a state in it that sets something in the + userdata key 'x'. Put another state machine inside of that state machine, + tell it to fetch the userdata key 'x'. Put a state that reads 'x' into + that nested state machine, and spew some info to rosout. + +Usage: + $> ./state_machine_nesting.py + +Output: + [INFO] : State machine starting in initial state 'SET' with userdata: + [] + [INFO] : State machine transitioning 'SET':'set_it'-->'NESTED' + [INFO] : State machine starting in initial state 'GET' with userdata: + ['x'] + [INFO] : >>> GOT DATA! x = hello + [INFO] : State machine terminating 'GET':'got_it':'done' + [INFO] : State machine terminating 'NESTED':'done':'succeeded' + +""" + +import rospy +import smach +import smach_ros + +# Define a state to set some user data +class Setter(smach.State): + def __init__(self, val): + smach.State.__init__(self, outcomes = ['set_it'], output_keys = ['x']) + self._val = val + def execute(self, ud): + # Set the data + ud.x = self._val + rospy.loginfo('>>> Set data: %s' % str(self._val)) + return 'set_it' + +# Define a state to get some user data +class Getter(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes = ['got_it'], input_keys = ['x']) + def execute(self, ud): + # Wait for data to appear + while 'x' not in ud: + rospy.loginfo('>>> Waiting for data...') + rospy.sleep(0.5) + rospy.loginfo('>>> GOT DATA! x = '+str(ud.x)) + return 'got_it' + +def main(): + rospy.init_node('smach_example_state_machine_nesting') + + # Create a SMACH state machine + sm0 = smach.StateMachine(outcomes=['succeeded']) + + # Open the container + with sm0: + # Add states to the container + smach.StateMachine.add('SET', Setter(val='hello'), {'set_it':'NESTED'}) + + sm1 = smach.StateMachine(outcomes=['done'], input_keys=['x']) + smach.StateMachine.add('NESTED', sm1, {'done':'succeeded'}) + with sm1: + smach.StateMachine.add('GET', Getter(), {'got_it':'done'}) + + # Execute SMACH plan + outcome = sm0.execute() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/state_machine_nesting2.py b/smach_tutorials/examples/state_machine_nesting2.py new file mode 100755 index 0000000..bac37df --- /dev/null +++ b/smach_tutorials/examples/state_machine_nesting2.py @@ -0,0 +1,79 @@ +#!/usr/bin/env python + +import rospy +import smach +import smach_ros + +# define state Foo +class Foo(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1','outcome2']) + self.counter = 0 + + def execute(self, userdata): + rospy.loginfo('Executing state FOO') + if self.counter < 3: + self.counter += 1 + return 'outcome1' + else: + return 'outcome2' + + +# define state Bar +class Bar(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAR') + return 'outcome1' + + + +# define state Bas +class Bas(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome3']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAS') + return 'outcome3' + + + + +def main(): + rospy.init_node('smach_example_state_machine') + + # Create the top level SMACH state machine + sm_top = smach.StateMachine(outcomes=['outcome5']) + + # Open the container + with sm_top: + + smach.StateMachine.add('BAS', Bas(), + transitions={'outcome3':'SUB'}) + + # Create the sub SMACH state machine + sm_sub = smach.StateMachine(outcomes=['outcome4']) + + # Open the container + with sm_sub: + + # Add states to the container + smach.StateMachine.add('FOO', Foo(), + transitions={'outcome1':'BAR', + 'outcome2':'outcome4'}) + smach.StateMachine.add('BAR', Bar(), + transitions={'outcome1':'FOO'}) + + smach.StateMachine.add('SUB', sm_sub, + transitions={'outcome4':'outcome5'}) + + # Execute SMACH plan + outcome = sm_top.execute() + + + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/state_machine_simple.py b/smach_tutorials/examples/state_machine_simple.py new file mode 100755 index 0000000..3d40057 --- /dev/null +++ b/smach_tutorials/examples/state_machine_simple.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python + +import rospy +import smach + +# define state Foo +class Foo(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1','outcome2']) + self.counter = 0 + + def execute(self, userdata): + rospy.loginfo('Executing state FOO') + if self.counter < 3: + self.counter += 1 + return 'outcome1' + else: + return 'outcome2' + + +# define state Bar +class Bar(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome2']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAR') + return 'outcome2' + + + + +# main +def main(): + rospy.init_node('smach_example_state_machine') + + # Create a SMACH state machine + sm = smach.StateMachine(outcomes=['outcome4', 'outcome5']) + + # Open the container + with sm: + # Add states to the container + smach.StateMachine.add('FOO', Foo(), + transitions={'outcome1':'BAR', + 'outcome2':'outcome4'}) + smach.StateMachine.add('BAR', Bar(), + transitions={'outcome2':'FOO'}) + + # Execute SMACH plan + outcome = sm.execute() + + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/state_machine_simple_introspection.py b/smach_tutorials/examples/state_machine_simple_introspection.py new file mode 100755 index 0000000..2b76526 --- /dev/null +++ b/smach_tutorials/examples/state_machine_simple_introspection.py @@ -0,0 +1,62 @@ +#!/usr/bin/env python + +import rospy +import smach +import smach_ros + +# define state Foo +class Foo(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome1','outcome2']) + self.counter = 0 + + def execute(self, userdata): + rospy.loginfo('Executing state FOO') + if self.counter < 3: + self.counter += 1 + return 'outcome1' + else: + return 'outcome2' + + +# define state Bar +class Bar(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes=['outcome2']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAR') + return 'outcome2' + + + + +# main +def main(): + rospy.init_node('smach_example_state_machine') + + # Create a SMACH state machine + sm = smach.StateMachine(outcomes=['outcome4', 'outcome5']) + + # Open the container + with sm: + # Add states to the container + smach.StateMachine.add('FOO', Foo(), + transitions={'outcome1':'BAR', + 'outcome2':'outcome4'}) + smach.StateMachine.add('BAR', Bar(), + transitions={'outcome2':'FOO'}) + + # Create and start the introspection server + sis = smach_ros.IntrospectionServer('my_smach_introspection_server', sm, '/SM_ROOT') + sis.start() + + # Execute SMACH plan + outcome = sm.execute() + + # Wait for ctrl-c to stop the application + rospy.spin() + sis.stop() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/user_data.py b/smach_tutorials/examples/user_data.py new file mode 100755 index 0000000..e087982 --- /dev/null +++ b/smach_tutorials/examples/user_data.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python +""" +Description: + Create a two-state state machine where one state writes to userdata and + the other state reads from userdata, and spews a message to rosout. + +Usage: + $> ./user_data.py + +Output: + [INFO] : State machine starting in initial state 'SET' with userdata: + [] + [INFO] : State machine transitioning 'SET':'set_it'-->'GET' + [INFO] : >>> GOT DATA! x = True + [INFO] : State machine terminating 'GET':'got_it':'succeeded' +""" + +import rospy +import smach +import smach_ros + +class Setter(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes = ['set_it'], output_keys = ['x']) + def execute(self, ud): + ud.x = True + return 'set_it' + +class Getter(smach.State): + def __init__(self): + smach.State.__init__(self, outcomes = ['got_it'], input_keys = ['x']) + def execute(self, ud): + rospy.loginfo('>>> GOT DATA! x = '+str(ud.x)) + return 'got_it' + +def main(): + rospy.init_node('smach_example_user_data') + + # Create a SMACH state machine + sm = smach.StateMachine(outcomes=['succeeded']) + + # Open the container + with sm: + # Add states to the container + smach.StateMachine.add('SET', Setter(), {'set_it':'GET'}) + smach.StateMachine.add('GET', Getter(), {'got_it':'succeeded'}) + + # Execute SMACH plan + outcome = sm.execute() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/examples/user_data2.py b/smach_tutorials/examples/user_data2.py new file mode 100755 index 0000000..056bd6d --- /dev/null +++ b/smach_tutorials/examples/user_data2.py @@ -0,0 +1,65 @@ +#!/usr/bin/env python + +import rospy +import smach +import smach_ros + +# define state Foo +class Foo(smach.State): + def __init__(self): + smach.State.__init__(self, + outcomes=['outcome1','outcome2'], + input_keys=['foo_counter_in'], + output_keys=['foo_counter_out']) + + def execute(self, userdata): + rospy.loginfo('Executing state FOO') + if userdata.foo_counter_in < 3: + userdata.foo_counter_out = userdata.foo_counter_in + 1 + return 'outcome1' + else: + return 'outcome2' + + +# define state Bar +class Bar(smach.State): + def __init__(self): + smach.State.__init__(self, + outcomes=['outcome1'], + input_keys=['bar_counter_in']) + + def execute(self, userdata): + rospy.loginfo('Executing state BAR') + rospy.loginfo('Counter = %f'%userdata.bar_counter_in) + return 'outcome1' + + + + + +def main(): + rospy.init_node('smach_example_state_machine') + + # Create a SMACH state machine + sm = smach.StateMachine(outcomes=['outcome4']) + sm.userdata.sm_counter = 0 + + # Open the container + with sm: + # Add states to the container + smach.StateMachine.add('FOO', Foo(), + transitions={'outcome1':'BAR', + 'outcome2':'outcome4'}, + remapping={'foo_counter_in':'sm_counter', + 'foo_counter_out':'sm_counter'}) + smach.StateMachine.add('BAR', Bar(), + transitions={'outcome1':'FOO'}, + remapping={'bar_counter_in':'sm_counter'}) + + + # Execute SMACH plan + outcome = sm.execute() + + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/mainpage.dox b/smach_tutorials/mainpage.dox new file mode 100644 index 0000000..4de1a7a --- /dev/null +++ b/smach_tutorials/mainpage.dox @@ -0,0 +1,26 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b smach_tutorials is ... + + + + +\section codeapi Code API + + + + +*/ diff --git a/smach_tutorials/package.xml b/smach_tutorials/package.xml new file mode 100644 index 0000000..3834b4d --- /dev/null +++ b/smach_tutorials/package.xml @@ -0,0 +1,32 @@ + + smach_tutorials + 0.1.10 + + This package contains numerous examples of how to use SMACH. + See the examples directory. + + Jonathan Bohren + Robert Haschke + Isaac I. Y. Saito + BSD + + http://wiki.ros.org/smach_tutorials + https://github.com/ros/common_tutorials + https://github.com/ros/common_tutorials/issues + + catkin + + message_generation + message_runtime + actionlib_msgs + actionlib + common_msgs + message_runtime + rospy + ros_tutorials + smach + smach_ros + turtlesim + + + diff --git a/smach_tutorials/scripts/usecase_01/executive_step_01.py b/smach_tutorials/scripts/usecase_01/executive_step_01.py new file mode 100755 index 0000000..01c81c2 --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/executive_step_01.py @@ -0,0 +1,41 @@ +#!/usr/bin/env python +""" +Description: + +Usage: + $> ./executive_step_01.py + +Output: + [ERROR] : InvalidTransitionError: State machine failed consistency check: + No initial state set. + + Available states: [] + [ERROR] : Container consistency check failed. + [ERROR] : InvalidTransitionError: State machine failed consistency check: + No initial state set. + + Available states: [] + [ERROR] : Container consistency check failed. +""" + +import rospy +import smach + +def main(): + rospy.init_node('smach_usecase_step_01') + + # Create a SMACH state machine + sm0 = smach.StateMachine(outcomes=[]) + + # Open the container + with sm0: + pass + + # Execute SMACH tree + outcome = sm0.execute() + + # Signal ROS shutdown (kill threads in background) + rospy.signal_shutdown('All done.') + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/scripts/usecase_01/executive_step_02.py b/smach_tutorials/scripts/usecase_01/executive_step_02.py new file mode 100755 index 0000000..7e26ff4 --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/executive_step_02.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python +""" +Description: + +Usage: + $> roslaunch turtle_nodes.launch + $> ./executive_step_02.py + +Output: + [INFO] : State machine starting in initial state 'RESET' with userdata: + [] + [INFO] : State machine transitioning 'RESET':'succeeded'-->'SPAWN' + [INFO] : State machine terminating 'SPAWN':'succeeded':'succeeded' + +""" + +import rospy + +import threading + +import smach +from smach import StateMachine, ServiceState, SimpleActionState + +import std_srvs.srv +import turtlesim.srv + +def main(): + rospy.init_node('smach_usecase_step_02') + + # Create a SMACH state machine + sm0 = StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Reset turtlesim + StateMachine.add('RESET', + ServiceState('reset', std_srvs.srv.Empty), + {'succeeded':'SPAWN'}) + + # Create a second turtle + StateMachine.add('SPAWN', + ServiceState('spawn', turtlesim.srv.Spawn, + request = turtlesim.srv.SpawnRequest(0.0,0.0,0.0,'turtle2'))) + + # Execute SMACH tree + outcome = sm0.execute() + + # Signal ROS shutdown (kill threads in background) + rospy.signal_shutdown('All done.') + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/scripts/usecase_01/executive_step_03.py b/smach_tutorials/scripts/usecase_01/executive_step_03.py new file mode 100755 index 0000000..23c05e3 --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/executive_step_03.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python +""" +Description: + +Usage: + $> roslaunch turtle_nodes.launch + $> ./executive_step_02.py + +Output: + [INFO] : State machine starting in initial state 'RESET' with userdata: + [] + [INFO] : State machine transitioning 'RESET':'succeeded'-->'SPAWN' + [INFO] : State machine terminating 'SPAWN':'succeeded':'succeeded' + +""" + +import rospy + +import threading + +import smach +from smach import StateMachine, ServiceState, SimpleActionState, IntrospectionServer + +import std_srvs.srv +import turtlesim.srv + +def main(): + rospy.init_node('smach_usecase_step_02') + + # Create a SMACH state machine + sm0 = StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Reset turtlesim + StateMachine.add('RESET', + ServiceState('reset', std_srvs.srv.Empty), + {'succeeded':'SPAWN'}) + + # Create a second turtle + StateMachine.add('SPAWN', + ServiceState('spawn', turtlesim.srv.Spawn, + request = turtlesim.srv.SpawnRequest(0.0,0.0,0.0,'turtle2'))) + + # Attach a SMACH introspection server + sis = IntrospectionServer('smach_usecase_01', sm0, '/USE_CASE') + sis.start() + + # Execute SMACH tree + outcome = sm0.execute() + + # Signal ROS shutdown (kill threads in background) + rospy.spin() + + sis.stop() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/scripts/usecase_01/executive_step_04.py b/smach_tutorials/scripts/usecase_01/executive_step_04.py new file mode 100755 index 0000000..46bdb0e --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/executive_step_04.py @@ -0,0 +1,96 @@ +#!/usr/bin/env python +""" +Description: + +Usage: + $> roslaunch turtle_nodes.launch + $> ./executive_step_04.py + +Output: + [INFO] : State machine starting in initial state 'RESET' with userdata: + [] + [INFO] : State machine transitioning 'RESET':'succeeded'-->'SPAWN' + [INFO] : State machine transitioning 'SPAWN':'succeeded'-->'TELEPORT1' + [INFO] : State machine transitioning 'TELEPORT1':'succeeded'-->'TELEPORT2' + [INFO] : State machine transitioning 'TELEPORT2':'succeeded'-->'BIG' + [WARN] : Still waiting for action server 'turtle_shape1' to start... is it running? + [INFO] : Connected to action server 'turtle_shape1'. + [INFO] 1279655938.783058: State machine transitioning 'BIG':'succeeded'-->'SMALL' + [INFO] 1279655975.025202: State machine terminating 'SMALL':'succeeded':'succeeded' + +""" + +import rospy + +import threading + +import smach +from smach import StateMachine, ServiceState, SimpleActionState, IntrospectionServer + +import std_srvs.srv +import turtlesim.srv +import turtle_actionlib.msg + + +def main(): + rospy.init_node('smach_usecase_step_04') + + # Construct static goals + polygon_big = turtle_actionlib.msg.ShapeGoal(edges = 11, radius = 4.0) + polygon_small = turtle_actionlib.msg.ShapeGoal(edges = 6, radius = 0.5) + + # Create a SMACH state machine + sm0 = StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Reset turtlesim + StateMachine.add('RESET', + ServiceState('reset', std_srvs.srv.Empty), + {'succeeded':'SPAWN'}) + + # Create a second turtle + StateMachine.add('SPAWN', + ServiceState('spawn', turtlesim.srv.Spawn, + request = turtlesim.srv.SpawnRequest(0.0,0.0,0.0,'turtle2')), + {'succeeded':'TELEPORT1'}) + + # Teleport turtle 1 + StateMachine.add('TELEPORT1', + ServiceState('turtle1/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(5.0,1.0,0.0)), + {'succeeded':'TELEPORT2'}) + + # Teleport turtle 2 + StateMachine.add('TELEPORT2', + ServiceState('turtle2/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(9.0,5.0,0.0)), + {'succeeded':'BIG'}) + + # Draw a large polygon with the first turtle + StateMachine.add('BIG', + SimpleActionState('turtle_shape1',turtle_actionlib.msg.ShapeAction, + goal = polygon_big), + {'succeeded':'SMALL'}) + + # Draw a small polygon with the second turtle + StateMachine.add('SMALL', + SimpleActionState('turtle_shape2',turtle_actionlib.msg.ShapeAction, + goal = polygon_small)) + + # Attach a SMACH introspection server + sis = IntrospectionServer('smach_usecase_01', sm0, '/USE_CASE') + sis.start() + + # Set preempt handler + smach.set_preempt_handler(sm0) + + # Execute SMACH tree in a separate thread so that we can ctrl-c the script + smach_thread = threading.Thread(target = sm0.execute) + smach_thread.start() + + # Signal handler + rospy.spin() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/scripts/usecase_01/executive_step_05.py b/smach_tutorials/scripts/usecase_01/executive_step_05.py new file mode 100755 index 0000000..3745514 --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/executive_step_05.py @@ -0,0 +1,106 @@ +#!/usr/bin/env python +""" +Description: + +Usage: + $> roslaunch turtle_nodes.launch + $> ./executive_step_06.py + +Output: + [INFO] : State machine starting in initial state 'RESET' with userdata: + [] + [INFO] : State machine transitioning 'RESET':'succeeded'-->'SPAWN' + [INFO] : State machine transitioning 'SPAWN':'succeeded'-->'TELEPORT1' + [INFO] : State machine transitioning 'TELEPORT1':'succeeded'-->'TELEPORT2' + [INFO] : State machine transitioning 'TELEPORT2':'succeeded'-->'DRAW_SHAPES' + [INFO] : Concurrence starting with userdata: + [] + [WARN] : Still waiting for action server 'turtle_shape2' to start... is it running? + [WARN] : Still waiting for action server 'turtle_shape1' to start... is it running? + [INFO] : Connected to action server 'turtle_shape2'. + [INFO] : Connected to action server 'turtle_shape1'. + [INFO] : Concurrent Outcomes: {'SMALL': 'succeeded', 'BIG': 'succeeded'} + [INFO] : State machine terminating 'DRAW_SHAPES':'succeeded':'succeeded' +""" + +import rospy + +import threading + +import smach +from smach import StateMachine, ServiceState, SimpleActionState, IntrospectionServer, Concurrence + +import std_srvs.srv +import turtlesim.srv +import turtle_actionlib.msg + + +def main(): + rospy.init_node('smach_usecase_step_05') + + # Construct static goals + polygon_big = turtle_actionlib.msg.ShapeGoal(edges = 11, radius = 4.0) + polygon_small = turtle_actionlib.msg.ShapeGoal(edges = 6, radius = 0.5) + + # Create a SMACH state machine + sm0 = StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Reset turtlesim + StateMachine.add('RESET', + ServiceState('reset', std_srvs.srv.Empty), + {'succeeded':'SPAWN'}) + + # Create a second turtle + StateMachine.add('SPAWN', + ServiceState('spawn', turtlesim.srv.Spawn, + request = turtlesim.srv.SpawnRequest(0.0,0.0,0.0,'turtle2')), + {'succeeded':'TELEPORT1'}) + + # Teleport turtle 1 + StateMachine.add('TELEPORT1', + ServiceState('turtle1/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(5.0,1.0,0.0)), + {'succeeded':'TELEPORT2'}) + + # Teleport turtle 2 + StateMachine.add('TELEPORT2', + ServiceState('turtle2/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(9.0,5.0,0.0)), + {'succeeded':'DRAW_SHAPES'}) + + # Draw some polygons + shapes_cc = Concurrence( + outcomes=['succeeded','aborted','preempted'], + default_outcome='aborted', + outcome_map = {'succeeded':{'BIG':'succeeded','SMALL':'succeeded'}}) + StateMachine.add('DRAW_SHAPES',shapes_cc) + with shapes_cc: + # Draw a large polygon with the first turtle + Concurrence.add('BIG', + SimpleActionState('turtle_shape1',turtle_actionlib.msg.ShapeAction, + goal = polygon_big)) + + # Draw a small polygon with the second turtle + Concurrence.add('SMALL', + SimpleActionState('turtle_shape2',turtle_actionlib.msg.ShapeAction, + goal = polygon_small)) + + + # Attach a SMACH introspection server + sis = IntrospectionServer('smach_usecase_01', sm0, '/USE_CASE') + sis.start() + + # Set preempt handler + smach.set_preempt_handler(sm0) + + # Execute SMACH tree in a separate thread so that we can ctrl-c the script + smach_thread = threading.Thread(target = sm0.execute) + smach_thread.start() + + # Signal handler + rospy.spin() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/scripts/usecase_01/executive_step_06.py b/smach_tutorials/scripts/usecase_01/executive_step_06.py new file mode 100755 index 0000000..91a544a --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/executive_step_06.py @@ -0,0 +1,141 @@ +#!/usr/bin/env python +""" +Description: + +Usage: + $> roslaunch turtle_nodes.launch + $> ./executive_step_06.py + +Output: + [INFO] : State machine starting in initial state 'RESET' with userdata: + + [INFO] : State machine transitioning 'RESET':'succeeded'-->'SPAWN' + [INFO] : State machine transitioning 'SPAWN':'succeeded'-->'TELEPORT1' + [INFO] : State machine transitioning 'TELEPORT1':'succeeded'-->'TELEPORT2' + [INFO] : State machine transitioning 'TELEPORT2':'succeeded'-->'DRAW_SHAPES' + [INFO] : Concurrence starting with userdata: + [] + [INFO] : State machine starting in initial state 'DRAW_WITH_MONITOR' with userdata: + [] + [INFO] : Concurrence starting with userdata: + [] + [WARN] : Still waiting for action server 'turtle_shape1' to start... is it running? + [WARN] : Still waiting for action server 'turtle_shape2' to start... is it running? + [INFO] : Connected to action server 'turtle_shape2'. + [INFO] : Connected to action server 'turtle_shape1'. + [INFO] : Preempt requested on action 'turtle_shape2' + [INFO] : Preempt on action 'turtle_shape2' cancelling goal: + edges: 6 + radius: 0.5 + [INFO] : Concurrent Outcomes: {'MONITOR': 'invalid', 'DRAW': 'preempted'} + [INFO] : State machine transitioning 'DRAW_WITH_MONITOR':'interrupted'-->'WAIT_FOR_CLEAR' + [INFO] : State machine transitioning 'WAIT_FOR_CLEAR':'invalid'-->'DRAW_WITH_MONITOR' + [INFO] : Concurrence starting with userdata: + [] + [INFO] : Concurrent Outcomes: {'MONITOR': 'preempted', 'DRAW': 'succeeded'} + [INFO] : State machine terminating 'DRAW_WITH_MONITOR':'succeeded':'succeeded' + [INFO] : Concurrent Outcomes: {'SMALL': 'succeeded', 'BIG': 'succeeded'} + [INFO] : State machine terminating 'DRAW_SHAPES':'succeeded':'succeeded' + +""" + +import rospy + +import threading +from math import sqrt, pow + +import smach +from smach import StateMachine, ServiceState, SimpleActionState, MonitorState, IntrospectionServer, Concurrence + +import std_srvs.srv +import turtlesim.srv +import turtlesim.msg +import turtle_actionlib.msg + + +def main(): + rospy.init_node('smach_usecase_step_06') + + # Construct static goals + polygon_big = turtle_actionlib.msg.ShapeGoal(edges = 11, radius = 4.0) + polygon_small = turtle_actionlib.msg.ShapeGoal(edges = 6, radius = 0.5) + + # Create a SMACH state machine + sm0 = StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Reset turtlesim + StateMachine.add('RESET', + ServiceState('reset', std_srvs.srv.Empty), + {'succeeded':'SPAWN'}) + + # Create a second turtle + StateMachine.add('SPAWN', + ServiceState('spawn', turtlesim.srv.Spawn, + request = turtlesim.srv.SpawnRequest(0.0,0.0,0.0,'turtle2')), + {'succeeded':'TELEPORT1'}) + + # Teleport turtle 1 + StateMachine.add('TELEPORT1', + ServiceState('turtle1/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(5.0,1.0,0.0)), + {'succeeded':'TELEPORT2'}) + + # Teleport turtle 2 + StateMachine.add('TELEPORT2', + ServiceState('turtle2/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(9.0,5.0,0.0)), + {'succeeded':'DRAW_SHAPES'}) + + # Draw some polygons + shapes_cc = Concurrence( + outcomes=['succeeded','aborted','preempted'], + default_outcome='aborted', + outcome_map = {'succeeded':{'BIG':'succeeded','SMALL':'succeeded'}}) + StateMachine.add('DRAW_SHAPES',shapes_cc) + with shapes_cc: + # Draw a large polygon with the first turtle + Concurrence.add('BIG', + SimpleActionState('turtle_shape1',turtle_actionlib.msg.ShapeAction, + goal = polygon_big)) + # Draw a small polygon with the second turtle + draw_monitor_cc = Concurrence( + ['succeeded','aborted','preempted'], + 'aborted', + child_termination_cb = lambda so: True, + outcome_map = { + 'succeeded':{'DRAW':'succeeded'}, + 'preempted':{'DRAW':'preempted','MONITOR':'preempted'}, + 'aborted':{'MONITOR':'invalid'}}) + Concurrence.add('SMALL',draw_monitor_cc) + with draw_monitor_cc: + Concurrence.add('DRAW', + SimpleActionState('turtle_shape2',turtle_actionlib.msg.ShapeAction, + goal = polygon_small)) + + def turtle_far_away(ud, msg): + """Returns True while turtle pose in msg is at least 1 unit away from (9,5)""" + if sqrt(pow(msg.x-9.0,2) + pow(msg.y-5.0,2)) > 2.0: + return True + return False + Concurrence.add('MONITOR', + MonitorState('/turtle1/pose',turtlesim.msg.Pose, + cond_cb = turtle_far_away)) + + # Attach a SMACH introspection server + sis = IntrospectionServer('smach_usecase_01', sm0, '/USE_CASE') + sis.start() + + # Set preempt handler + smach.set_preempt_handler(sm0) + + # Execute SMACH tree in a separate thread so that we can ctrl-c the script + smach_thread = threading.Thread(target = sm0.execute) + smach_thread.start() + + # Signal handler + rospy.spin() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/scripts/usecase_01/executive_step_07.py b/smach_tutorials/scripts/usecase_01/executive_step_07.py new file mode 100755 index 0000000..471fa5b --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/executive_step_07.py @@ -0,0 +1,155 @@ +#!/usr/bin/env python +""" +Description: + +Usage: + $> roslaunch turtle_nodes.launch + $> ./executive_step_06.py + +Output: + [INFO] : State machine starting in initial state 'RESET' with userdata: + + [INFO] : State machine transitioning 'RESET':'succeeded'-->'SPAWN' + [INFO] : State machine transitioning 'SPAWN':'succeeded'-->'TELEPORT1' + [INFO] : State machine transitioning 'TELEPORT1':'succeeded'-->'TELEPORT2' + [INFO] : State machine transitioning 'TELEPORT2':'succeeded'-->'DRAW_SHAPES' + [INFO] : Concurrence starting with userdata: + [] + [INFO] : State machine starting in initial state 'DRAW_WITH_MONITOR' with userdata: + [] + [INFO] : Concurrence starting with userdata: + [] + [WARN] : Still waiting for action server 'turtle_shape1' to start... is it running? + [WARN] : Still waiting for action server 'turtle_shape2' to start... is it running? + [INFO] : Connected to action server 'turtle_shape2'. + [INFO] : Connected to action server 'turtle_shape1'. + [INFO] : Preempt requested on action 'turtle_shape2' + [INFO] : Preempt on action 'turtle_shape2' cancelling goal: + edges: 6 + radius: 0.5 + [INFO] : Concurrent Outcomes: {'MONITOR': 'invalid', 'DRAW': 'preempted'} + [INFO] : State machine transitioning 'DRAW_WITH_MONITOR':'interrupted'-->'WAIT_FOR_CLEAR' + [INFO] : State machine transitioning 'WAIT_FOR_CLEAR':'invalid'-->'DRAW_WITH_MONITOR' + [INFO] : Concurrence starting with userdata: + [] + [INFO] : Concurrent Outcomes: {'MONITOR': 'preempted', 'DRAW': 'succeeded'} + [INFO] : State machine terminating 'DRAW_WITH_MONITOR':'succeeded':'succeeded' + [INFO] : Concurrent Outcomes: {'SMALL': 'succeeded', 'BIG': 'succeeded'} + [INFO] : State machine terminating 'DRAW_SHAPES':'succeeded':'succeeded' + +""" + +import rospy + +import threading +from math import sqrt, pow + +import smach +from smach import StateMachine, ServiceState, SimpleActionState, MonitorState, IntrospectionServer, Concurrence + +import std_srvs.srv +import turtlesim.srv +import turtlesim.msg +import turtle_actionlib.msg + + +def main(): + rospy.init_node('smach_usecase_step_06') + + # Construct static goals + polygon_big = turtle_actionlib.msg.ShapeGoal(edges = 11, radius = 4.0) + polygon_small = turtle_actionlib.msg.ShapeGoal(edges = 6, radius = 0.5) + + # Create a SMACH state machine + sm0 = StateMachine(outcomes=['succeeded','aborted','preempted']) + + # Open the container + with sm0: + # Reset turtlesim + StateMachine.add('RESET', + ServiceState('reset', std_srvs.srv.Empty), + {'succeeded':'SPAWN'}) + + # Create a second turtle + StateMachine.add('SPAWN', + ServiceState('spawn', turtlesim.srv.Spawn, + request = turtlesim.srv.SpawnRequest(0.0,0.0,0.0,'turtle2')), + {'succeeded':'TELEPORT1'}) + + # Teleport turtle 1 + StateMachine.add('TELEPORT1', + ServiceState('turtle1/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(5.0,1.0,0.0)), + {'succeeded':'DRAW_SHAPES'}) + + # Draw some polygons + shapes_cc = Concurrence( + outcomes=['succeeded','aborted','preempted'], + default_outcome='aborted', + outcome_map = {'succeeded':{'BIG':'succeeded','SMALL':'succeeded'}}) + StateMachine.add('DRAW_SHAPES',shapes_cc) + with shapes_cc: + # Draw a large polygon with the first turtle + Concurrence.add('BIG', + SimpleActionState('turtle_shape1',turtle_actionlib.msg.ShapeAction, + goal = polygon_big)) + + # Draw a small polygon with the second turtle + small_shape_sm = StateMachine(outcomes=['succeeded','aborted','preempted']) + Concurrence.add('SMALL',small_shape_sm) + with small_shape_sm: + # Teleport turtle 2 + StateMachine.add('TELEPORT2', + ServiceState('turtle2/teleport_absolute', turtlesim.srv.TeleportAbsolute, + request = turtlesim.srv.TeleportAbsoluteRequest(9.0,5.0,0.0)), + {'succeeded':'DRAW_WITH_MONITOR'}) + + # Construct a concurrence for the shape action and the monitor + draw_monitor_cc = Concurrence( + ['succeeded','aborted','preempted','interrupted'], + 'aborted', + child_termination_cb = lambda so: True, + outcome_map = { + 'succeeded':{'DRAW':'succeeded'}, + 'preempted':{'DRAW':'preempted','MONITOR':'preempted'}, + 'interrupted':{'MONITOR':'invalid'}}) + + StateMachine.add('DRAW_WITH_MONITOR', + draw_monitor_cc, + {'interrupted':'WAIT_FOR_CLEAR'}) + + with draw_monitor_cc: + Concurrence.add('DRAW', + SimpleActionState('turtle_shape2',turtle_actionlib.msg.ShapeAction, + goal = polygon_small)) + def turtle_far_away(ud, msg): + """Returns True while turtle pose in msg is at least 1 unit away from (9,5)""" + if sqrt(pow(msg.x-9.0,2) + pow(msg.y-5.0,2)) > 2.0: + return True + return False + Concurrence.add('MONITOR', + MonitorState('/turtle1/pose',turtlesim.msg.Pose, + cond_cb = turtle_far_away)) + + StateMachine.add('WAIT_FOR_CLEAR', + MonitorState('/turtle1/pose',turtlesim.msg.Pose, + cond_cb = lambda ud,msg: not turtle_far_away(ud,msg)), + {'valid':'WAIT_FOR_CLEAR','invalid':'TELEPORT2'}) + + + # Attach a SMACH introspection server + sis = IntrospectionServer('smach_usecase_01', sm0, '/USE_CASE') + sis.start() + + # Set preempt handler + smach.set_preempt_handler(sm0) + + # Execute SMACH tree in a separate thread so that we can ctrl-c the script + smach_thread = threading.Thread(target = sm0.execute) + smach_thread.start() + + # Signal handler + rospy.spin() + +if __name__ == '__main__': + main() diff --git a/smach_tutorials/scripts/usecase_01/turtle_nodes.launch b/smach_tutorials/scripts/usecase_01/turtle_nodes.launch new file mode 100644 index 0000000..a0ee91d --- /dev/null +++ b/smach_tutorials/scripts/usecase_01/turtle_nodes.launch @@ -0,0 +1,9 @@ + + + + + + + + +