He, Peng

A Roboticist.

Be Focused & Cool.


ROS Actionlib: The Generated Messages

Abstract: Knowing how to write an action server is very useful in robot software development. This guidance will focus on explaining the missing part from the official ROS tutorial -- the relation between an action server, and its generated messages.

There are three ways of passing data in ROS:

  1. regular topics: the regulars
  2. service calls: only putting data on the bus when you requested
  3. action calls: real world long time actions, ROS method for threading

1&2 should always be in computer time and return the data without a human-noticeable delay. I'm putting down here an example to help you to understand a service call scenario better. Therefore, you can easily decide, something should be a service or an action.

Service call example

Getting a robot status data. When you have a case that you want to get the robot status(which may contain you raw sensor data as well as some calculation between the data), now you notice that "I don't need this robot status very often, only give me when a user has asked for it; however, ROS, by default, if you have a node subscribe to a topic, then this topic will keep publishing. Now a service call - method will be very efficient at here. You will get the status data only when you make a service request, and this topic will not take your bandwidth away.

Package File Structure

I expect you have gone through the ROS Actionlib tutorial already and know how to create an action message. So you should have some package containing a similar file structure.

my_package
├── action
│   └── Fetch.action
├── launch
│   └── automation.launch
├── msg
│   └── ActuatorCMD.msg
├── scripts
│   ├── action_controller.py
│   └── action_fetch_server.py
├── package.xml
├── CMakeLists.txt
└── README.md

The Confusion In Generated Messages

Here is my custom action message, same pattern from ROS tutorial:

# Define the goal
string  cmd_id
float32 distance
---
# Define the result
string  cmd_id
bool    is_reached
---
# Define a feedback message
string cmd_id
float32 error

Messages with "Action" keyword in it

Now let me explain the magic behind it. After you catkin_make the package, these seven messages will be generated:

$ ls devel/share/my_package/msg/

FetchAction.msg           # Feed this name for your callback function's topic type

FetchActionGoal.msg       # The msgs with a word Action in it
FetchActionResult.msg     # are all used as the topic callback msg type
FetchActionFeedback.msg   # that you should use when declaring the function     

FetchGoal.msg             # The msgs without Action in it
FetchResult.msg           # are the msgs  you should use to create an actual
FetchFeedback.msg         # data structure for the results or feedback

Down below you can find the msgs with an Action name in it are actually wrapped with a header and an actionlib_msgs/GoalID for the actionlib mechnism.

$ cat FetchAction.msg 
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
FetchActionGoal action_goal
FetchActionResult action_result
FetchActionFeedback action_feedback

$ cat FetchActionGoal.msg 
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
Header header
actionlib_msgs/GoalID goal_id
FetchGoal goal

Messages without "Action" keyword in it

The msgs without Action keyword in it are the context you declared between the --- in the action msg file. This is quite confusing for myself at least the first time, I used all FetchActionGoal to create the goal msg for my results and it of course not work, furthermore, the error message made me even confused about what was going on.

$ cat FetchGoal.msg 
# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
# Define the goal
string  cmd_id
float32 distance

Publish Your Action Goal

I believe now you have a clear understanding of when&which message you should use when writing the code. For my habit, I always give out a short example of it: (the examples are usually for a better understanding, they may not actually run if you copy them)


self.server = actionlib.SimpleActionServer('/my_topic/action/fetch_server', FetchAction, self.execute, auto_start=False)

result_msg = FetchResult()
result_msg.cmd_id = msg.cmd_id

result_msg.is_reached = True if self.task_done else False
self.server.set_succeeded(result_msg, 'Fetch action succeeded!')

For more about the actionlib workflow, please check out the other post here

Recent Posts

ROS Import Python Module From Another Package

Abstract: This will be a fire to go blog. It is really not hard to do this but ROS wiki did a good j…

In ROS, Python, CMakeLIstsRead More
Earlier Posts

Regular Expression Simple Usage in Python

Abstract: I feel the regular expression is a monster, in both ways. Hard to learn, hard to use. Be…

In Python, Study & Research, Regular ExpressionRead More
comments powered by Disqus