Action
到目前为止,我们已经知道ROS提供了两种基本的节点之间通信方式:发布和订阅主题、 请求服务。主题订阅的方式解耦了数据生产者与消费者之间的关系,但是当生产者想要获取消息的消费情况时, 系统就会变复杂,我们还需要再订阅一个反馈消息的主题。而服务的方式可以满足我们希望获得反馈的需求,但是这种反馈也只是在服务结束之后给出,如果我们想要跟进一个任务的进度, 纯粹使用服务请求模式也会把系统搞得很复杂。因而,ROS提供了第三种节点间通信方式:Action。
Action可以看做是两种基本通信方式的组合,它像服务器模式那样,提供了一种请求响应机制。又像订阅者模式那样,不断地发布反馈消息。比如说,控制移动机器人从A点运动到B点, 我们就可以通过Action的形式来实现,我们请求机器人运动,在运动过程中可以实时监视机器人的位置,完成任务后还可以反馈完成状态,而且可以在运动过程中打断任务。 实际上,ROS的Navigation技术栈就是这么实现的。
本文根据官方教程,进行一些总结和调整,来介绍ROS的Action机制和使用方法。为了方便描述, 我们先用catkin工具创建一个test_action包。如下所示,指令后面的那些参数用来描述其依赖的包。
$ catkin_create_pkg test_action actionlib message_generation roscpp rospy std_msgs actionlib_msgs
1. Action机制
ROS提供了一个actionlib的工具,用于实现Action机制。下图(a)中示例了Action系统构成, Action客户端和服务器提供了简单的API函数,通过功能请求(function call)和回调(callback),来请求和执行Action。Action客户端和服务器之间, 则通过ROS Action Protocol来实现通信。
ROS Action Protocol实际上一系列ROS Topic,如下图1(b)所示。Action客户端发布goal和cancel主题的消息到服务器,用于请求和取消一个Action。而Action的服务器, 则发布了status、result和feedback三个主题到客户端,用于反馈Action的执行状态和执行结果。
a). Action系统构成 | b). Action接口 |
图 1. Action机制 |
客户端通过发送主题goal的消息来告知服务器一个新的Action目标。这个主题的消息实际上是在用户定义的消息类型基础上,添加了一个时间戳和目标ID。 这两个字段的内容实际上是由图1中所示的Action client提供的。但是有些简单的client实现可能不添加这些内容,那么Action server将以当前ROS系统时间为消息打戳。 如果客户端没有提供动作ID,那么它对于客户端而言就没有什么意义,因为客户端没有任何手段获知服务器分配的ID。
客户端发送cancel主题的数据,通知服务器取消特定的动作。该主题的消息类型是[actionlib_msgs/GoalID],我们可以通过rosmsg工具查看它。它有两个stamp(时间戳)和id两个字段。 如果消息中将这两个字段都置空,那么将取消所有的目标。如果给了时间戳,那么将取消该时间戳之前的所有任务。如果给了ID将取消该ID指定的任务。
$ rosmsg show actionlib_msgs/GoalID
time stamp
string id
服务器会以一个固定的频率,一般是10Hz,发送一个status主题的消息到客户端,通知它正在执行的所有Action的状态。[actionlib_msgs/GoalStatusArray]是status主题的消息类型, 我们同样可以通过rosmsg工具查看其信息格式如下。
右图中给出了Action机制的状态机,上面是服务器的,下面是客户端的。具体的状态意义不再细讲,可以参考官方文档。 需要注意的是客户端的状态机是一个跟随状态机,它接收到服务器的状态机变动之后,对应的完成自身的状态跳转。
$ rosmsg show actionlib_msgs/GoalStatusArray
std_msgs/Header header
uint32 seq
time stamp
string frame_id
actionlib_msgs/GoalStatus[] status_list
uint8 PENDING=0
uint8 ACTIVE=1
uint8 PREEMPTED=2
uint8 SUCCEEDED=3
uint8 ABORTED=4
uint8 REJECTED=5
uint8 PREEMPTING=6
uint8 RECALLING=7
uint8 RECALLED=8
uint8 LOST=9
actionlib_msgs/GoalID goal_id
time stamp
string id
uint8 status
string text
主题result和feedback是服务器用于告知客户端Action的执行结果和反馈信息的。这两个主题与goal一样都是在用户描述的消息基础上添加Goal ID用以区分不同的Action。 对于一个Action而言反馈是执行过程中的状态是一个可选项,而告知执行结果则是必需的。因此,即使用户并没有描述result消息,服务器也会在Action完成后的一段时间内发布result主题的消息。 该消息中将告知Action的运行状态(Rejected, Recalled, Preempted, Aborted, Succeeded)。
#goal definition
int32 order
---
#result definition
int32[] sequence
---
#feedback
int32[] sequence
2. Action文件
在ROS中,对应主题有*.msg文件,对应服务有*.srv文件。相应的,Action机制也有专门的消息类型描述格式,用*.action文件来描述。*.action文件有goal,result和feedback三个部分组成, 比如右边所示的,官方教程中的"fibonacci.action"。
我们在test_action的根目录下创建一个action的子目录,并把右边的教程文件拷贝到该子目录下。然后对CMakeLists.txt添加如下的依赖关系。
- 添加对actionlib_msgs包的依赖,如果我们通过catkin_create_package创建包的时候,添加了对actionlib_msgs的依赖,那么在自动生成的CMakeLists.txt中就已经描述了这个依赖关系。
find_package(catkin REQUIRED COMPONENTS actionlib_msgs)
- 通过add_action_files声明我们创建的*.action文件,并调用generate_messages生成消息,并指定其依赖关系。
add_action_files(DIRECTORY action FILES Fibonacci.action) generate_messages(DEPENDENCIES actionlib_msgs std_msgs)
- 将对actionlib_msgs的依赖关系添加到catkin_pacakge中。
add_action_files(DIRECTORY action FILES Fibonacci.action) generate_messages(DEPENDENCIES actionlib_msgs std_msgs)
此外,我们最好确认package.xml描述文件中记录了对message_generation的依赖关系。
<build_depend>message_generation</build_depend>
添加了上述的信息之后,我们就可以回到工作空间下进行编译,并查看生成的msg文件。貌似action在ROS中的支持力度不够,并没有提供什么有力的工具来查看关于action的信息,所以目前只能用这种土办法了。
$ cd $CATKIN_WORK_SPACE
$ catkin_make
$ ls devel/share/test_action/msg/
FibonacciActionFeedback.msg FibonacciActionResult.msg FibonacciResult.msg
FibonacciActionGoal.msg FibonacciFeedback.msg
FibonacciAction.msg FibonacciGoal.msg
$ ls devel/include/test_action/
FibonacciActionFeedback.h FibonacciActionResult.h FibonacciResult.h
FibonacciActionGoal.h FibonacciFeedback.h
FibonacciAction.h FibonacciGoal.h
3. Action服务器
下面我们在src子目录下创建test_action_server.cpp的文件,实现计算斐波纳契序列的Action服务器。首先包含必要的头文件,其中"ros.h"是ROS系统的头文件,提供了ROS的API。 "simple_action_server.h"是由actionlib提供的一个Action服务器,为用户的服务器应用提供了Action的API。而"FibonacciAction.h"则是从我们刚刚创建的*.action文件生成的头文件。
#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include <test_action/FibonacciAction.h>
接下来,我们定义一个指向服务器的指针。在main函数中完成ROS系统的初始化,构造Action服务器,并开启之。在下面的第10行中,我们创建了一个服务器actionServer。 并在第11和12行中用指针pServer指向了该对象,调用start()函数开启服务。
actionlib::SimpleActionServer<test_action::FibonacciAction> *pServer;
int main(int argc, char *argv[])
{
ros::init(argc, argv, "test_action_server");
ros::NodeHandle nh_;
actionlib::SimpleActionServer<test_action::FibonacciAction> actionServer(nh_, "test_action_server", execute, false);
pServer = &actionServer;
pServer->start();
ros::spin();
return 0;
}
在构造服务器对象的时候,我们传递了四个参数,其中nh_是ROS的句柄,"test_action_server"则是服务器名称;execute是一个回调函数,当服务器接收到goal主题消息后就会调用该函数; 最后的那个false没研究是干嘛的。所有的服务都是由函数execute提供,下面是其具体实现,它需要一个参数goal,它是一个指针指示着接收到的goal消息。
void execute(const test_action::FibonacciGoalConstPtr &goal)
{
ROS_INFO_STREAM("fibonacci:" << goal->order);
接下来,构造一些必要的局部变量。其中feedback用于反馈消息,result用于完成服务之后报告结束消息。在服务之前,我们先对feedback进行初始化,放入'0'和'1'作为以后的斐波纳契数列的计算起点。
ros::Rate rate(10);
bool success = true;
test_action::FibonacciFeedback feedback;
test_action::FibonacciResult result;
feedback.sequence.clear();
feedback.sequence.push_back(0);
feedback.sequence.push_back(1);
然后,我们用一个for循环计算数列元素。在每次循环中,我们先判定服务器和ROS系统的状态,如果被抢占则切换服务器对象的状态为Preempted并退出循环。一切正常的话,我们就更新feedback消息, 并通过pServer发布反馈消息。
for (int i = 1; i <= goal->order; i++) {
if (pServer->isPreemptRequested() || !ros::ok()) {
ROS_INFO_STREAM("fibonacci: Preempted");
pServer->setPreempted();
success = false;
break;
}
feedback.sequence.push_back(feedback.sequence[i] + feedback.sequence[i-1]);
pServer->publishFeedback(feedback);
rate.sleep();
}
当我们成功的结束了循环,意味着达到了目标goal。此时我们更新result消息并通过服务器对象发布之。
if (success) {
result.sequence = feedback.sequence;
ROS_INFO_STREAM("fibonacci: Succeeded");
pServer->setSucceeded(result);
}
}
要编译该服务器,我们还需要在CMakeLists.txt中添加如下的编译指示。
add_executable(test_action_server src/test_action_server.cpp)
set_target_properties(test_action_server PROPERTIES LINKER_LANGUAGE CXX)
target_link_libraries(test_action_server ${catkin_LIBRARIES})
4. Action客户端
在src子目录下创建test_action_client.cpp文件,实现一个Action客户端。首先包含必要的头文件,"simple_action_client.h"为应用程序提供了Action client的接口, "terminal_state.h"则描述和提供了Action状态机的接口。
#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <actionlib/client/terminal_state.h>
#include <test_action/FibonacciAction.h>
在下面的main函数中,我们先完成ROS系统的初始化,然后通过action名称"test_action_server"构建Action客户端对象。
int main(int argc, char *argv[])
{
ros::init(argc, argv, "test_action_client");
actionlib::SimpleActionClient<test_action::FibonacciAction> actionClient("test_action_server", true);
接着检查服务器存在后,我们通过对象actionClient发布一个goal消息请求Action。
ROS_INFO_STREAM("Waiting for action server to start.");
actionClient.waitForServer();
ROS_INFO_STREAM("server started, sending goal.");
test_action::FibonacciGoal goal;
goal.order = 20;
actionClient.sendGoal(goal);
之后,我们就等着Action结束。运行该客户端后,我们将看到,如果服务器成功完成了任务,将返回一个Secceeded的状态。
bool isSuccess = actionClient.waitForResult(ros::Duration(30.0));
if (isSuccess) {
actionlib::SimpleClientGoalState state = actionClient.getState();
ROS_INFO_STREAM("Finished:" << state.toString());
} else {
ROS_INFO_STREAM("Action did not finish before the time out.");
}
return 0;
}
同样的,我们还需要在CMakeLists.txt中添加如下语句,用于指导编译。
add_executable(test_action_client src/test_action_client.cpp)
set_target_properties(test_action_client PROPERTIES LINKER_LANGUAGE CXX)
target_link_libraries(test_action_client ${catkin_LIBRARIES})
5. Action Demo
通过如下的指令,先后运行服务器和客户端。如果不出意外,我们将看到类似下面的日志。
$ roscore
$ rosrun test_action test_action_server
[ INFO] [1561817362.444853116]: fibonacci:20
[ INFO] [1561817382.447745721]: fibonacci: Succeeded
$ rosrun test_action test_action_client
[ INFO] [1561817362.216258195]: Waiting for action server to start.
[ INFO] [1561817362.444050365]: server started, sending goal.
[ INFO] [1561817382.448508385]: Finished:SUCCEEDED
通过指令$ rqt_graph
我们可以看到下图所示的系统运行图。从图中,可以看到当前运行的test_action_server和test_action_client两个节点之间,
通过goal, cancel, status, result和feedback建立起联系。
我们还可以通过rostopic指令查看服务器发布的feedback消息,也可以在自己写的节点中订阅这一消息。
$ rostopic echo /test_action_server/feedback
header:
seq: 0
stamp:
secs: 1561818161
nsecs: 290977145
frame_id: ''
status:
goal_id:
stamp:
secs: 1561818161
nsecs: 287716804
id: "/test_action_client-1-1561818161.287716804"
status: 1
text: "This goal has been accepted by the simple action server"
feedback:
sequence: [0, 1, 1]
6. 总结
本文中,我们认识了ROS的Action机制。本质上它仍然是一种Topic机制,只是通过actionlib进行了封装。在服务器和客户端之间通过goal, cancel, status, feedback, result五个主题实现Action机制。 类似的,我们通过*.action文件来描述Action的消息结构。此外我们还介绍了如何实现简单的Action服务器和客户端。