(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

User Data Passing

Description: This tutorial gives an example of two states passing user data to each other.

Tutorial Level: BEGINNER

Next Tutorial: Nesting State Machines

All of the following examples can be run without modification. They can be found in the smach_tutorials package in the examples directory. The comments at the head of each file show roughly what the output from running the script should look like.

state_machine2.png

https://raw.githubusercontent.com/eacousineau/executive_smach_tutorials/hydro-devel/smach_tutorials/examples/user_data2.py

   1 #!/usr/bin/env python
   2 
   3 import roslib; roslib.load_manifest('smach_tutorials')
   4 import rospy
   5 import smach
   6 import smach_ros
   7 
   8 # define state Foo
   9 class Foo(smach.State):
  10     def __init__(self):
  11         smach.State.__init__(self, 
  12                              outcomes=['outcome1','outcome2'],
  13                              input_keys=['foo_counter_in'],
  14                              output_keys=['foo_counter_out'])
  15 
  16     def execute(self, userdata):
  17         rospy.loginfo('Executing state FOO')
  18         if userdata.foo_counter_in < 3:
  19             userdata.foo_counter_out = userdata.foo_counter_in + 1
  20             return 'outcome1'
  21         else:
  22             return 'outcome2'
  23 
  24 
  25 # define state Bar
  26 class Bar(smach.State):
  27     def __init__(self):
  28         smach.State.__init__(self, 
  29                              outcomes=['outcome1'],
  30                              input_keys=['bar_counter_in'])
  31         
  32     def execute(self, userdata):
  33         rospy.loginfo('Executing state BAR')
  34         rospy.loginfo('Counter = %f'%userdata.bar_counter_in)        
  35         return 'outcome1'
  36         
  37 
  38 
  39 
  40 
  41 def main():
  42     rospy.init_node('smach_example_state_machine')
  43 
  44     # Create a SMACH state machine
  45     sm = smach.StateMachine(outcomes=['outcome4'])
  46     sm.userdata.sm_counter = 0
  47 
  48     # Open the container
  49     with sm:
  50         # Add states to the container
  51         smach.StateMachine.add('FOO', Foo(), 
  52                                transitions={'outcome1':'BAR', 
  53                                             'outcome2':'outcome4'},
  54                                remapping={'foo_counter_in':'sm_counter', 
  55                                           'foo_counter_out':'sm_counter'})
  56         smach.StateMachine.add('BAR', Bar(), 
  57                                transitions={'outcome1':'FOO'},
  58                                remapping={'bar_counter_in':'sm_counter'})
  59 
  60 
  61     # Execute SMACH plan
  62     outcome = sm.execute()
  63 
  64 
  65 if __name__ == '__main__':
  66     main()

Wiki: smach/Tutorials/User Data Passing (last edited 2016-01-21 10:02:14 by JavierVGomez)