title | subtitle | author | urlcolor | colorlinks |
---|---|---|---|---|
A simple example |
ROS2-Pytransitions State Machine Package |
a.whit ([email protected]) |
blue |
true |
This example illustrates the basic functionality and usage of the
ros_transitions
package. It assumes that the Python code is executed in a
properly configured ROS environment. See the
end of this document for instructions for
running this example.
The state machine chosen for this example is based on the
phase transitions example described in the
pytransitions
documentation. More generally, ros_transitions
should work with any pytransitions
machine.
First, define a simple class to represent physical matter. For now, this class does nothing, and will simply be used as a state machine model.1
>>> class Matter:
... pass
Initialize a pytransitions state machine by defining a set of states and
transitions that represent the phases of matter. Set the initial state to
solid
.
>>> import transitions
>>> model = Matter()
>>> states = ['solid', 'liquid', 'gas']
>>> machine = transitions.Machine(model=model, states=states, initial='solid')
>>> machine.add_transition('melt', source='solid', dest='liquid')
>>> machine.add_transition('freeze', source='liquid', dest='solid')
>>> machine.add_transition('vaporize', source='liquid', dest='gas')
>>> machine.add_transition('condense', source='gas', dest='liquid')
The combination of machine
and model
is enough to define a
pytransitions
state machine. See the
pytransitions documentation for further examples
and usage information.
The next step is to make the state machine available to ROS. Initialize ROS and
create a ros_transitions
node, to wrap machine
. This makes
the state machine available to other nodes on the ROS graph.
>>> import rclpy
>>> import ros_transitions
>>> rclpy.init()
>>> node = ros_transitions.Node(machine=machine)
That's it. The state machine is now connected to ROS.2
What have we accomplished? To observe the ROS state machine in action, we need to monitor relevant ROS2 topics and messages. Create a second ROS2 node to listen for state changes.
>>> import rclpy.node
>>> client_node = rclpy.node.Node('client')
Subscribe the client node to the state
topic, and define a callback function
that will print state transitions, as they happen.3
>>> from ros_transitions import state_message
>>> state_callback = lambda m: print(f'State: {m.data}', flush=True)
>>> subscription = client_node.create_subscription(msg_type = state_message,
... topic ='machine/state',
... callback = state_callback,
... qos_profile = 5);
Initialize a publisher for sending triggers to the state machine node.
>>> from ros_transitions import trigger_message
>>> publisher = client_node.create_publisher(msg_type = trigger_message,
... topic ='machine/trigger',
... qos_profile = 5);
Define simple lambda functions for simplifying the process of updating the state machine via ROS.
>>> spin = lambda n: rclpy.spin_once(n, timeout_sec=0.005)
>>> trigger = lambda s: publisher.publish(trigger_message(data=s))
Test the state machine node by triggering a state transition, and then passing
control4 to the ros_transitions
node, so that any relevant
messages may be published to the ROS graph.
>>> result = trigger('melt') # result = model.melt()
>>> spin(client_node)
>>> spin(node)
Allow the client node to process any ROS messages that it might receive.
>>> spin(client_node)
State: liquid
This shows that a state transition message was sent from the ros_transitions
node to the client node, in order to indicate that the state machine
transitioned from the solid
state to the liquid
state. Trigger another
transition.
>>> result = trigger('vaporize') # result = model.vaporize()
>>> spin(client_node)
>>> spin(node)
>>> spin(client_node)
State: gas
Finally, return to the original state.
>>> result = trigger('condense') # result = model.condense()
>>> spin(client_node)
>>> spin(node)
>>> spin(client_node)
State: liquid
>>> result = trigger('freeze') # result = model.freeze()
>>> spin(client_node)
>>> spin(node)
>>> spin(client_node)
State: solid
To cleanly exit, destroy the nodes and shut down ROS.
>>> node.destroy_node()
>>> client_node.destroy_node()
>>> rclpy.shutdown()
It is also possible to monitor the activity of the ros_transitions
state
machine using ROS command line tools, in a
second configured environment. For example,
the topics created by the node can be listed as follows, at the shell command
line.
> ros2 topic list
/machine/event
/machine/state
/parameter_events
/rosout
To print state transition messages, use the topic echo
command.
> ros2 topic echo /machine/state
Note: If command line tools are preferred, then it is not necessary to create a client node in the Python example.
The Markdown source code for this example can be run directly as a doctest, using the following code.
import doctest
doctest.testfile('simple_example.md')
Footnotes
-
Other examples will use more complex models. ↩
-
The node still must be spun before it can process ROS messages. Refer to the next section. ↩
-
In addition to the
machine/state
topic, a subscription to themachine/event
topic could also be initialized. ↩ -
We pass control of the process to the ROS2 executor -- for a single cycle -- via the spin_once command. ↩