tutorial
ROS

Creating ROS 1 Actions

Coordinate open-ended communication between your ROS 1 nodes

tutorial
ROS

There are several different ways that ROS 1 nodes can share information with each other. They can publish an ongoing stream of data via topics, or initiate one-off requests via services.

Actions are a final way for ROS nodes to communicate with each other. They combine the best of both worlds, using both open-ended data streams and discrete requests to execute long-running tasks.

In this tutorial, we’ll discuss how ROS actions work, when to use them, and how to implement a simple action client and server in Python.

How do ROS 1 actions work?

With topics, nodes follow a publisher-subscriber model – a node publishes messages on a topic, while other nodes subscribe to that topic. Services, on the other hand, follow a request-response (RPC) model – a client node makes a request to a server node, then waits for an asynchronous response.

Under the hood, ROS 1 actions are built on top of several topics, although they do have to be activated by a service. ROS 2 actions, on the other hand, introduce a completely new interface that integrates the topics and services used in a single type definition.

At a high level, a client node initiates an action by sending a goal to a server node via a topic (step 1 in diagram below). Once that server node acknowledges the goal with a response, it will start publishing feedback, or updates on its progress towards that goal, on a separate topic (step 2). Meanwhile, the client node publishes another request for the action’s result (step 3). Once the goal succeeds or fails, the action server sends back a response on the result topic.

ROS actions

How can we use ROS 1 actions?

Their three-part architecture – goal, feedback, and result – makes ROS actions especially well-suited for long-running tasks. It’s no surprise, then, that actions are most often used by robots for navigation tasks.

If a fleet operator wanted to send a warehouse AMR to a particular aisle a few minutes away, for example, they can initiate a ROS action with that destination as the goal. While on its journey, the robot could broadcast feedback back to the operator about how far it has traveled along its designated route.

If requirements change, and the operator decides to send the AMR to a different aisle, they have the option to cancel the first action and initiate a new one to reroute the robot to a different destination. Otherwise, if the robot successfully reaches its destination, it sends a final confirmation back to the operator, confirming its arrival.

Defining an action

Now that we know how actions work, and when they can be used, let's write some code!

For this exercise, let's create an action that alerts a warehouse robot when it's time for it to start its shift. The action should start counting down from a given number, broadcast updates as it progresses, then finally announce when it’s reached zero.

Actions are defined in .action files, with 3 sections separated by ---:

# Request
---
# Result
---
# Feedback

In a ROS 1 package, create an action/ directory with a Countdown.action file. Let’s include a starting_num for the countdown in the request, the current_num in the feedback, and confirmation that the countdown is_finished in the result:

# Request
int32 starting_num
---
# Result
bool is_finished
---
# Feedback
int32 current_num

Before we can use this action, we have to pass the definition to the ROS 1 code generation pipeline. Additionally, we are going to use the actionlib and actionlib_msgs packages. The first one contains the libraries and tools needed to interact with the action servers whereas the second one contains specific messages used in this interaction.

In ROS 2, these packages are integrated into a single one called action, which contains both the libraries, tools and the new action type definition.

Proceed by adding the following lines to your CMakeLists.txt file, before the catkin_package() line:

find_package(catkin REQUIRED COMPONENTS
actionlib
genmsg
actionlib_msgs
rospy
)

# Before catkin_package()
add_action_files(DIRECTORY action FILES Countdown.action)
generate_messages(DEPENDENCIES actionlib_msgs)

We should also add the required dependencies to our package.xml:

<depend>rospy</depend>

<depend>actionlib</depend>

<depend>actionlib_msgs</depend>

You can now navigate to the root of your package, and build it with your action definition:

$ catkin_make

Source your workspace, then check that the action built successfully:

$ . devel/setup.bash $
$ rosmsg list | grep -i my_ros1_package
my_ros1_package/CountdownAction
my_ros1_package/CountdownActionFeedback
my_ros1_package/CountdownActionGoal
my_ros1_package/CountdownActionResult
my_ros1_package/CountdownFeedback
my_ros1_package/CountdownGoal
my_ros1_package/CountdownResult

As you can see, the Action file has been split into several messages that will be communicated through topics. The messages that contain Action in the name are the ones sent from the client to the server, while the others are the ones published by the server. In ROS 2, with the new interface, the action created will be contained in a single type.

Writing an action server

Let’s write an action server that counts down from our Countdown action request’s starting_num.

Create a countdown_server.py file in your package script folder and import the following packages:

import rospy
import actionlib
import time
import my_ros1_package.msg

Create a CountdownServer class. Then, create an action server that specifies the node for the action client to attach to (self), the action type (CountdownAction), the action name ("countdown"), and a callback function for handling goals from the client (execute_callback). After this, you can start the server:

class CountdownServer():
# Create Feedback and Result messages
def __init__(self):
# Create the server
self._action_server = actionlib.SimpleActionServer('countdown', my_ros1_package.msg.CountdownAction, self.execute_callback, False)

# Start the server
self._action_server.start()
rospy.loginfo("Starting Action Server")

Next, define the execute_callback function as one that logs a helpful message ("Starting countdown…"), indicates that the goal succeeded, and then returns a result:

# Callback function to run after acknowledging a goal from the client
def execute_callback(self, goal_handle):
rospy.loginfo("Starting countdown…")


result = my_ros1_package.msg.CountdownResult()
result.is_finished = True
# Indicate that the goal was successful
self._action_server.set_succeeded(result)

Finally, let’s initialize ROS 1 and spin up an instance of this CountdownServer class:

def main(args=None):
# Init ROS1 and give the node a name
rospy.init_node("countdown_server")
countdown_server = CountdownServer()
rospy.spin()

if __name__ == '__main__':
main()

In a Terminal window, run roscore:

$ roscore

In a second Terminal window, run your action server:

$ python3 src/my_ros1_package/scripts/countdown_server.py

In a third window, use rostopic pub to send a goal:

$ rostopic pub /countdown/goal my_ros1_package/CountdownActionGoal "header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
goal_id:
stamp:
secs: 0
nsecs: 0
id: ''
goal:
starting_num: 5"

In the window where you have run the server, you should see "Starting countdown…".

If you wish to see the feedback and result, you will need two additional terminals. In one you will run:

$ rostopic echo /countdown/feedback

And in the last one, run:

$ rostopic echo /countdown/result.

Now, when you call the server, you should see something like this:

terminal windows

Top, L to R: tabs for roscore and sending goal, action serverBottom, L to R: feedback topic, result topic

Now that we’ve verified our server is running, let’s actually count down from our goal’s starting_num:

import time

# other imports

class CountdownServer():
# other methods

# Callback function to run after acknowledging a goal from the client`

def execute_callback(self, goal_handle):
rospy.loginfo("Starting countdown…")

# Initiate the feedback message's current_num as the action request's starting_num
feedback_msg = my_ros1_package.msg.CountdownFeedback()
feedback_msg.current_num = goal_handle.starting_num

while feedback_msg.current_num>0:
# Publish feedback
self._action_server.publish_feedback(feedback_msg)


# Print log messages
rospy.loginfo('Feedback: {0}'.format(feedback_msg.current_num))


# Decrement the feedback message's current_num
feedback_msg.current_num = feedback_msg.current_num - 1

# Wait a second before counting down to the next number
time.sleep(1)

self._action_server.publish_feedback(feedback_msg)
rospy.loginfo('Feedback: {0}'.format(feedback_msg.current_num))
rospy.loginfo('Done!')

result = my_ros1_package.msg.CountdownResult()
result.is_finished = True
# Indicate that the goal was successful
self._action_server.set_succeeded(result)

This time, if you re-run all our original commands, you should see the feedback being printed:

# In separate Terminal windows:
$ roscore
$ python3 src/my_ros1_package/scripts/countdown_server.py
$ rostopic echo /countdown/feedback
$ rostopic echo /countdown/result
$ rostopic pub /countdown/goal my_ros1_package/CountdownActionGoal "header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
goal_id:
stamp:
secs: 0
nsecs: 0
id: ''
goal:
starting_num: 5"
terminal windows

Top, L to R: tabs for roscore and sending goal, action serverBottom, L to R: feedback topic, result topic

Writing an action client

Now that we have a server working, let’s write the client that will initiate the request to your server.

Create a new countdown_client.py file, and import the following packages:

import rospy
import actionlib
import my_ros1_package.msg

Once again, we create a class (CountdownClient ) It should contain an action client that specifies the node for the client to attach to (self), the action type (Countdown), and the action name ("countdown"):

class CountdownClient():
def __init__(self):
# Initializes "countdown_client" node
self._action_client = actionlib.SimpleActionClient("countdown", my_ros1_package.msg.CountdownAction)

As we discussed, the primary function of a client is to send a goal to the server:

# Waits for server to be available, then sends goal
def send_goal(self, starting_num):
goal_msg = my_ros1_package.msg.CountdownGoal()
goal_msg.starting_num = starting_num
rospy.loginfo('Starting at: {0}'.format(starting_num))
rospy.loginfo('Waiting for server...')

self._action_client.wait_for_server()

# Returns future to goal handle; client runs feedback_callback after sending the goal
self._send_goal_future = self._action_client.send_goal(goal_msg, active_cb=self.goal_response_callback, feedback_cb=self.feedback_callback, done_cb = self.get_result_callback)

rospy.loginfo("Goal sent!")

Once the goal is acknowledged by the server, we want to be able to access whether it was accepted and whether it reached a successful result:

# Run when client accepts goal
def goal_response_callback(self):
rospy.loginfo('Goal accepted :)')

# Run when client sends feedback
def feedback_callback(self, feedback_msg):
rospy.loginfo('Received feedback: {0}'.format(feedback_msg.current_num))

# Run when client sends final result
def get_result_callback(self, state, result):
# Show log and exit node
rospy.loginfo('Result: {0}'.format(result.is_finished))
rospy.signal_shutdown("Shutting-down client node")

Finally, initialize ROS and spin up the client node:

def main(args=None):
# Init ROS1 and give the node a name
rospy.init_node("countdown_client")
action_client = CountdownClient()

# Sends goal and waits until it's completed
action_client.send_goal(10)
rospy.spin()

if __name__ == '__main__':
main()

Run roscore, your action server, and your action client:

# In separate Terminal windows:
$ roscore
$ python3 src/my_ros1_package/scripts/countdown_server.py
$ python3 src/my_ros1_package/scripts/countdown_client.py

In the server window, you should see feedback messages printing as the server executes the goal:

[INFO] [1660842257.519973]: Starting Action server
[INFO] [1660842264.685694]: Starting countdown…
[INFO] [1660842264.687922]: Feedback: 10
[INFO] [1660842265.690994]: Feedback: 9
[INFO] [1660842266.698688]: Feedback: 8
[INFO] [1660842267.706357]: Feedback: 7
[INFO] [1660842268.710408]: Feedback: 6
[INFO] [1660842269.717961]: Feedback: 5
[INFO] [1660842270.722799]: Feedback: 4
[INFO] [1660842271.729141]: Feedback: 3
[INFO] [1660842272.733695]: Feedback: 2
[INFO] [1660842273.737373]: Feedback: 1
[INFO] [1660842274.744387]: Feedback: 0
[INFO] [1660842274.749348]: Done!

In the client window, you should see messages about the goal’s status, the ongoing feedback, and eventually the final result.

[INFO] [1660842264.616643]: Starting at: 10
[INFO] [1660842264.620893]: Waiting for server...
[INFO] [1660842264.685264]: Goal sent!
[INFO] [1660842264.686136]: Goal accepted :)
[INFO] [1660842264.688148]: Received feedback: 10
[INFO] [1660842265.692482]: Received feedback: 9
[INFO] [1660842266.700141]: Received feedback: 8
[INFO] [1660842267.706853]: Received feedback: 7
[INFO] [1660842268.710949]: Received feedback: 6
[INFO] [1660842269.718680]: Received feedback: 5
[INFO] [1660842270.723924]: Received feedback: 4
[INFO] [1660842271.729387]: Received feedback: 3
[INFO] [1660842272.734261]: Received feedback: 2
[INFO] [1660842273.738948]: Received feedback: 1
[INFO] [1660842274.745158]: Received feedback: 0
[INFO] [1660842274.752481]: Result: True

You've created your first working ROS action client and server!

“Compile” Python

Until now, we have been using the command python3 to launch our nodes. If you want to run them using the command rosrun, you must edit the catkin_install_python section of your CMakeLists.txt:

catkin_install_python(PROGRAMS
   scripts/countdown_server.py
   scripts/countdown_client.py
   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Now "compile" your workspace again:

$ catkin_make

Remember to source your workspace for every new terminal you open:

$ . devel/setup.bash

Now you can run your nodes using the rosrun command! This way, you do not need to specify the complete path of your script file:

# In separate Terminal windows:
$ roscore
$ rosrun my_ros1_package countdown_server.py
$ rosrun my_ros1_package countdown_client.py

Summary

By leveraging the strengths of both topics and services, ROS 1 actions are able to set goals, make progress on those goals, and broadcast when they’ve succeeded.

We hope this tutorial helped you get a better understanding of how you might use ROS actions in the larger scheme of your robot’s architecture. For a reference to all the code covered in this post, check out our foxglove/tutorials GitHub repo.

As always, feel free to reach out to the Foxglove team in our Discord community to ask questions, give us feedback, and request a topic for the next tutorial!

Read more

Start building with Foxglove.

Get started for free