(!) 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.

Passing User Data between States

Description: This tutorial teaches you how to pass data from one state(machine) to the next state(machine).

Tutorial Level: BEGINNER

Next Tutorial: Create a hierarchical state machine

Specifying User Data

A state could require some input data to do its work, and/or it could have some output data it wants to provide to other states. The input and output data of a state is called userdata of the state. When you construct a state, you can specify the names of the userdata fields it needs/provides.

   1   class Foo(smach.State):
   2      def __init__(self, outcomes=['outcome1', 'outcome2'],
   3                         input_keys=['foo_input'],
   4                         output_keys=['foo_output'])
   5 
   6      def execute(self, userdata):
   7         # Do something with userdata
   8         if userdata.foo_input == 1:
   9             return 'outcome1'
  10         else:
  11             userdata.foo_output = 3
  12             return 'outcome2'
  • The input_keys list enumerates all the inputs that a state needs to run. A state declares that it expect these fields to exist in the userdata. The execute method is provided a copy of the userdata struct. The state can read from all userdata fields that it enumerates in the input_keys list, but it can't write to any of these fields.

  • The output_keys list enumerates all the outputs that a state provides. The state can write to all fields in the userdata struct that are enumerated in the output_keys list.

/!\ Note: Objects obtained from userdata via input_keys are wrapped for immutability, thus a state cannot call methods on these objects. If you require a mutable input object, you must specify the same key in both input_keys and output_keys. If you are not passing objects, or you do not need to call methods on or modify them, you should use unique names in input_keys and output_keys, to avoid confusion and potential bugs.

user_data_single.png

The interface to a state is defined by its outcomes, its input keys and its output keys.

Connecting User Data

When adding states to a state machine, you also need to connect the user data fields, to allow states to pass data to each other. For example, if state FOO produces 'foo_output', and state BAR needs 'bar_input', then you can attach these two user data ports together using name remapping:

   1   sm_top = smach.StateMachine(outcomes=['outcome4','outcome5'],
   2                           input_keys=['sm_input'],
   3                           output_keys=['sm_output'])
   4   with sm_top:
   5      smach.StateMachine.add('FOO', Foo(),
   6                             transitions={'outcome1':'BAR',
   7                                          'outcome2':'outcome4'},
   8                             remapping={'foo_input':'sm_input',
   9                                        'foo_output':'sm_data'})
  10      smach.StateMachine.add('BAR', Bar(),
  11                             transitions={'outcome2':'FOO'},
  12                             remapping={'bar_input':'sm_data',
  13                                        'bar_output1':'sm_output'})

The remapping field maps the in/output_key of a state to a userdata field of the state machine. So when you remap 'x':'y':

  • x needs to be an input_key or an output_key of the state, and
  • y will automatically become part of the userdata of the state machine.

/!\ Note that remapping is not required when the user data names used in your state are the same as the user data names used by the state machine. However, remapping makes the connections very explicit, so it is recommended to always specify remapping, even something like "remapping={'a':'a'}".

Passing data between states

We can use the remapping mechanism to pass data from state FOO to state BAR. To accomplish this, we need one remapping when adding FOO, and one remapping when adding BAR:

  • FOO: remapping={'foo_output':'sm_user_data'}
  • BAR: remapping={'bar_input':'sm_user_data'}

Passing data between state machines and states

We can also use the remapping mechanism to pass data from a state BAR to the state machine that contains BAR. If 'sm_output' is an output key of the state machine:

  • BAR: remapping={'bar_output':'sm_output'}

Or, the opposite, we can pass data from the state machine to a state FOO. If 'sm_input' is an input key of the state machine:

  • FOO: remapping={'foo_input':'sm_input'}

user_data.png

Example

This is a complete runnable example you can find in the executive_smach_tutorials package.

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()

Running the example:

 $ roscd smach_tutorials
 $ ./examples/user_data2.py

The next tutorial teaches you how to nest different state machines, creating a hierarchical state machine.

Wiki: smach/Tutorials/User Data (last edited 2020-08-06 13:52:17 by RobertZickler)