[ROS in 5 mins] 032 – How to compile ROS Action messages

[ROS in 5 mins] 032 - How to compile ROS Action messages

Written by Ruben Alves

03/09/2018

Hello ROS Developers!

In today’s tutorial we are going learn how to create a ROS Action specification file, how to compile ROS Action messages and how to import them.

You can run the commands used along the video in your own computer if you have ROS installed, but you can also use Robot Ignite Academy in case you don’t want to deal with ROS installation. Robot Ignite Academy, by the way, is the best tool if you want to Learn ROS Fast.

Before we start, if you are new to ROS and want complete courses on that subject, I highly recommend you taking any of the following courses on Robot Ignite Academy:

Ok, let’s get started.

Creating a ROS Package

In order to create our custom ROS Action we need a package on the catkin_ws (catkin workspace), so let’s create one called actions_tutorial using the commands below:

source /opt/ros/$ROS_DISTRO/setup.bash

mkdir ~/catkin_ws/src/ -p

cd ~/catkin_ws/src

catkin_create_pkg actions_tutorial rospy std_msgs actionlib_msgs

Ok, so far so good. We now have package called actions_tutorial, now let’s move to the next step.

Creating a ROS Action file

Let’s suppose our robot is able to wash dishes, so, let’s create an action file called WashTheDishes.action and place it inside a folder called action which will be on the package we just created.

cd ~/catkin_ws/src/actions_tutorial

mkdir action

cd action/

touch WashTheDishes.action

Now let’s put some content on that WashTheDishes.action file. Please use the content below:

# Goal
int32 number_of_minutes

---
# Result
string[] dishes_washed

---
# Feedback
string last_dish_washed

If you look carefully on the content of the WashTheDishes.action file you can find 3 sections. Goal, Result and Feedback. Goal is what we send to the Action Server, which in this case will be the number_of_minutes that our robot need to work, the Result is the list named dishes_washed that we will receive once the robot finishes working. Given that an action can take a long time depending on the goal parameter, we have a Feedback section that we will receive whenever the robot finishes washing a dish. The feedback in this case we named last_dish_washed.

Now let’s go to the next step

Compiling a ROS Action file

On our actions_tutorial package you have a file called CMakeLists.txt that is created automatically when we create a package. That file is used to compile our package. If we look at that file you can see some instructions on how to modify it to compile our own messages. The instructions on that file says that we have to modifly the package.xmlfile that is located inside our package folder and add message_generation and message_runtime on that file. To make it easier, below we have the full content of the  package.xml after the modifications.

<?xml version="1.0"?>
<package format="2">
<name>actions_tutorial</name>
<version>0.0.0</version>
<description>The actions_tutorial package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="user@todo.todo">user</maintainer>


<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>

<!-- Use build_depend for packages you need at compile time: -->
<build_depend>message_generation</build_depend>
<!-- Use exec_depend for packages you need at runtime: -->
<exec_depend>message_runtime</exec_depend>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>actionlib_msgs</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>actionlib_msgs</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>actionlib_msgs</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>


<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->

</export>
</package>

The CMakeLists.txt also says that we have to modify that file itself by doing the following:

  1. Add message_generation to thefind_package() section
  2. Add message_runtime to the catkin_package section
  3. Add WashTheDishes.action to the add_action_files section
  4. Uncomment the generate_messages section.

To make your life easier, below we have t he full content of that actions_tutorial/CMakeLists.txt file after our modifications:

cmake_minimum_required(VERSION 2.8.3)
project(actions_tutorial)

## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
actionlib_msgs
rospy
std_msgs
message_generation
)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)


## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )

## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )

## Generate actions in the 'action' folder
add_action_files(
FILES
WashTheDishes.action
)

## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
actionlib_msgs# std_msgs
)

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed

## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
LIBRARIES actions_tutorial
CATKIN_DEPENDS actionlib_msgs rospy std_msgs
DEPENDS system_lib
DEPENDS message_runtime
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)

## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/actions_tutorial.cpp
# )

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/actions_tutorial_node.cpp)

## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")

## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_actions_tutorial.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

Ok, now that we have our CMakeLists.txt and package.xml files modified, we can compile our message using the commands below:

cd ~/catkin_ws/

catkin_make

If everything goes ok, at the end you should see a message saying that your package has been 100% compiled:

user:~/catkin_ws$ catkin_make
Base path: /home/user/catkin_ws
Source space: /home/user/catkin_ws/src
Build space: /home/user/catkin_ws/build
Devel space: /home/user/catkin_ws/devel
Install space: /home/user/catkin_ws/install
####
#### Running command: "make cmake_check_build_system" in "/home/user/catkin_ws/build"
####
-- Using CATKIN_DEVEL_PREFIX: /home/user/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /opt/ros/kinetic
-- This workspace overlays: /opt/ros/kinetic
-- Using PYTHON_EXECUTABLE: /usr/bin/python
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: ON
-- Call enable_testing()
-- Using CATKIN_TEST_RESULTS_DIR: /home/user/catkin_ws/build/test_results
-- Found gmock sources under '/usr/src/gmock': gmock will be built
-- Found gtest sources under '/usr/src/gmock': gtests will be built
-- Using Python nosetests: /usr/local/bin/nosetests-2.7
-- catkin 0.7.14
-- BUILD_SHARED_LIBS is on
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~ traversing 1 packages in topological order:
-- ~~ - actions_tutorial
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'actions_tutorial'
-- ==> add_subdirectory(actions_tutorial)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- Generating .msg files for action actions_tutorial/WashTheDishes /home/user/catkin_ws/src/actions_tutorial/action/WashTheDishes.action
-- actions_tutorial: 7 messages, 0 services
CMake Warning at /opt/ros/kinetic/share/catkin/cmake/catkin_package.cmake:166 (message):
catkin_package() DEPENDS on 'system_lib' but neither
'system_lib_INCLUDE_DIRS' nor 'system_lib_LIBRARIES' is defined.
Call Stack (most recent call first):
/opt/ros/kinetic/share/catkin/cmake/catkin_package.cmake:102 (_catkin_package)
actions_tutorial/CMakeLists.txt:105 (catkin_package)

...

Scanning dependencies of target actions_tutorial_generate_messages_cpp
[ 83%] Generating C++ code from actions_tutorial/WashTheDishesFeedback.msg
[ 86%] Generating C++ code from actions_tutorial/WashTheDishesGoal.msg
[ 89%] Generating C++ code from actions_tutorial/WashTheDishesActionResult.msg
[ 91%] Generating C++ code from actions_tutorial/WashTheDishesAction.msg
[ 94%] Generating C++ code from actions_tutorial/WashTheDishesResult.msg
[ 97%] Generating C++ code from actions_tutorial/WashTheDishesActionGoal.msg
[100%] Generating C++ code from actions_tutorial/WashTheDishesActionFeedback.msg
[100%] Built target actions_tutorial_generate_messages_cpp
Scanning dependencies of target actions_tutorial_generate_messages
[100%] Built target actions_tutorial_generate_messages

Once our package is successfully compiled, we have to source our catkin_ws in order to let ROS know how to locate our custom action. Let’s do it with the command below:

source ~/catkin_ws/devel/setup.bash 

Ok, so far we have seen how to create and how to compile our custom action. Now let’s import it to make sure it has been successfully compiled. An easy way to do that is by running the command below:

python -c 'from actions_tutorial.msg import WashTheDishesAction; print "Hey, it worked!!!"' 

After running the command I just mentioned you should be able to see the message “Hey, it worked!!!”.

This messages confirms that our message was successfully compiled and imported.

You can also use rosmsg list | grep Dishes to find your message. The output should be something like:

user:~/catkin_ws$ rosmsg list | grep Dishes
actions_tutorial/WashTheDishesAction
actions_tutorial/WashTheDishesActionFeedback
actions_tutorial/WashTheDishesActionGoal
actions_tutorial/WashTheDishesActionResult
actions_tutorial/WashTheDishesFeedback
actions_tutorial/WashTheDishesGoal
actions_tutorial/WashTheDishesResult

So, that is the tutorial for today, guys. Now that you know how to compile your ROS Action Messages, you should keep pushing and learn how to create your own ROS Action Server: https://www.theconstruct.ai/ros-5-mins-033-create-ros-action-server/

We are constantly adding new tutorials here and videos in our YouTube channel.  If you like the content, please consider subscribing to our channel on YouTube, giving us a thumbs up there and even leaving comments on the comments section of the video.

By the way, below we have a video that shows the content of this post:

Masterclass 2023 batch2 blog banner

Check Out These Related Posts

1 Comment

  1. Raymond

    Please help here, when I run Python code python -c ‘from actions_tutorial.msg import WashTheDishesAction; print “Hey, it worked!!!”‘ .

    I got error No module named yaml.

    I tried to install pyyaml, but it is already the latest version.

    Reply

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This