以下是最后一种通信机制action-server/action-client,尽管与service/client通信机制很像,它与service/client通信机制还是有很关键的不同点的:
与service/client通信相似的是:
当然,action-servers和action-clients的框架里面还有很多功能和变量,可以在http://wiki.ros.org/actionlib 中查看,这里只列出一个简单的应用。
①依然使用catkin_simple
功能来创建package
cs_create_pkg example_action_server roscpp actionlib
②然后在新建的package中创建一个**action**package用来存储action messages的信息,方法与创建service messages一样。
cd example_action_server
mkdir action
③惯例,在package.xml文件中添加两行生成消息文件的语句:
<build_depend>message_generationbuild_depend>
<run_depend>message_runtimerun_depend>
与之前定义msg消息和service消息很相似,都需要建立一个对应格式的消息文件
其中,service messages比起简单的messages要复杂一些,而action的消息跟service的消息很类似,也有分多个区域,总体上要稍微复杂一点
service消息有两个消息区域
action消息有三个消息区域
以下是本例要创建的一个action消息
①先进入到action的文件夹,创建一个名称为demo.action的文件:
cd action
touch demo.action
②然后写入如下内容:
#goal definition
int32 input
---
#result definition
int32 output
int32 goal_stamp
---
#feedback
int32 fdbk
三个消息区域通过三个连字符分隔开,最上面的是goad,中间的是result,最下面的feedback,“#”开头的注释语句不是必须的,可以省略。
注意,顺序不可以打乱,严格按照以上顺序排列
③跟着就可以进行编译生成action消息类型的头文件了
catkin_make
生成的头文件在
~/ros_ws/devel/include/packageName
这里的packageName是example_action_server,里面有7个头文件,如下图
其中,以demoAction.h为主,其他六个头文件都包含在该头文件中,要调用该包中的action消息类型,只需要知道demoAction.h这个头文件的名称即可。
以下是一个action server节点的代码:
#include<ros/ros.h> //惯例添加
#include <actionlib/server/simple_action_server.h> //这是一个library里面一个做好的包(simple_action_server)里面的头文件
#include<example_action_server/demoAction.h> //这个头文件是重点,在上一部分生成的action消息的头文件
int g_count = 0;
bool g_count_failure = false;
class ExampleActionServer {
private:
ros::NodeHandle nh_; // 节点句柄
actionlib::SimpleActionServer<example_action_server::demoAction> as_;//创建一个名称为"as_"的“SimpleActionServer”,SimpleActionServer是一个在actionlib里面的类(在actionlib的包中有定义),消息类型为example_action_server::demoAction,即上部分定义的action消息类型
// 以下三个是与client交流传递的消息类型
example_action_server::demoGoal goal_; // 接收clients发送的goal message的变量
example_action_server::demoResult result_; // 保存result结果信息的变量,当完成goad的请求后将结果信息发送给client
example_action_server::demoFeedback feedback_; //在这个例子中没有用到feedback信息,它起一个反馈作用,将一定信息反馈给client,具体参数根据实际需要设定,如 as_.publishFeedback(feedback_); ,就可以将变量“feedback_”发送给client
public:
ExampleActionServer(); //在类定义之外定义构造函数的主体
~ExampleActionServer(void) {
}
// Action接口
void executeCB(const actionlib::SimpleActionServer<example_action_server::demoAction>::GoalConstPtr& goal);
};
ExampleActionServer::ExampleActionServer() :
as_(nh_, "example_action", boost::bind(&ExampleActionServer::executeCB, this, _1),false)
//执行上述构造函数:成员as_将通过指定的节点句柄(nh_)来实例化, 并在接收到goad消息后执行一个函数(executeCB),这个函数是类(ExampleActionServer)中的一个成员方法(member method)
// 在这里定义了server的名称叫为“example_action”,这个名称很重要,server和client通信需要知道这个名字
//“this”会告诉“boost::bind”这个函数是类的成员
//“_1”被“boost::bind”用来通知“simple action server”,回调函数(executeCB)只取一个数值
//“false”的意思是暂时不启动这个server(在这个构造函数中的后面会启动server)
{
ROS_INFO("in constructor of exampleActionServer...");
as_.start(); //在上述的初始化参数使用false,先不启动action server,到这里才启动,就是要确保server的实例化对象要先完成之后再启动这个实例化对象,避免出现意外状况
}
//下面是具体的executeCBD(成员方法)的执行函数
//example_action_server::demoAction上部分定义的action消息类型
void ExampleActionServer::executeCB(const actionlib::SimpleActionServer<example_action_server::demoAction>::GoalConstPtr& goal) {
//result消息由两个成员组成,一个是“input”,它保存的是clients发送过来的goal消息,另一个是“goal_stamp”,记录接收goal消息的次数
g_count++; // 从server启动开始追踪被执行的goal消息数量
result_.output = g_count; // 在这里使用在类中定义过的成员变量result_
result_.goal_stamp = goal->input;
//检测clients和server是否保持同步状态
if (g_count != goal->input) {
ROS_WARN("hey--mismatch!");
ROS_INFO("g_count = %d; goal_stamp = %d", g_count, result_.goal_stamp);
g_count_failure = true; //set a flag to commit suicide
ROS_WARN("informing client of aborted goal");
as_.setAborted(result_); // 这个函数的意思是放弃这个goad并发送result消息通知client
}
else {
as_.setSucceeded(result_); // 这个函数的意思是成功执行这个goad并发送result消息通知client
}
}
int main(int argc, char** argv) {
ros::init(argc, argv, "demo_action_server_node"); //初始化,命名该节点
ROS_INFO("instantiating the demo action server: ");
ExampleActionServer as_object; // 创建类(ExampleActionServer)的一个实例化对象
ROS_INFO("going into spin");
// 从这里开始,所有的工作都是在action server中的成员方法(executeCB())完成的
// 在action server(example_action)下有五个topic: cancel, feedback, goal, result, status
while (!g_count_failure && ros::ok()) {
ros::spinOnce();
}
return 0;
}
在和action server同一个package中建立一个example_aciton_client.cpp文件,以下是一个action client节点的代码:
#include<ros/ros.h>
#include <actionlib/client/simple_action_client.h> //与server一样,client也需要使用actionlib library里面的头文件,只是使用的是simple_action_client.h
#include<example_action_server/demoAction.h> //上一部分定义的action messages文件
//下面这个函数是非必要的,当goal完成时就会调用这个函数一次,但这也是一种访问server中“result”消息的便捷方式
void doneCb(const actionlib::SimpleClientGoalState& state,
const example_action_server::demoResultConstPtr& result) {
ROS_INFO(" doneCb: server responded with state [%s]", state.toString().c_str());
int diff = result->output - result->goal_stamp;
ROS_INFO("got result output = %d; goal_stamp = %d; diff = %d", result->output, result->goal_stamp, diff);
}
int main(int argc, char** argv) {
ros::init(argc, argv, "demo_action_client_node"); //初始化,命名节点
int g_count = 0;//这是一个与server兼容的goal消息的对象
example_action_server::demoGoal goal;实例化一个类型为“example_action_server::demoGoal”的对象
actionlib::SimpleActionClient<example_action_server::demoAction> action_client("example_action", true);
//action_client是“actionlib::SimpleActionClient”实例化的对象,使用的消息类型是“example_action_server::demoAction”
// “example_action”是server的名字,在action server节点中命名的
//参数“true”是为了说明新的client将作为一个单线程运行
// 以下开始连接server:
ROS_INFO("waiting for server: ");
bool server_exists = action_client.waitForServer(ros::Duration(5.0)); //等待5秒,若括号内不设置时间,会一直等待
// 有一点很奇怪,好像并没有等地5秒,但是如果server没有运行却会很快会有返回值
if (!server_exists) {
ROS_WARN("could not connect to server; halting");
return 0; // 输出一个警报消息,这部分也是非必要的
}
ROS_INFO("connected to action server"); // 成功连接
while (true) {
// 开始给goal消息赋值
g_count++;
goal.input = g_count; // 这只是一个按序列编号发送的goal消息
//action_client.sendGoal(goal); // 只发送goal消息
action_client.sendGoal(goal, &doneCb); // 在发送goal消息时可以使用一个额外的回调函数来检测goal的执行情况
// action_client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb); //可以同时调用多个回调函数
bool finished_before_timeout = action_client.waitForResult(ros::Duration(5.0));//等待result消息5秒,同样,去掉括号内的数值,会一直等待
//若没有接收到result消息,则发出警报
if (!finished_before_timeout) {
ROS_WARN("giving up waiting on result for goal number %d", g_count);
return 0;
} else {
//否则,就说明server反馈了result消息给我们
}
}
return 0;
}
这里的client和server是在同一个package里面的,很多时候同一个server有很多个clients,而且都是在不同的package,这时候就需要在package.xml文件里面添加action messages包的依赖项,同时还要在client节点的文件中加上action messages的头文件。
还需要在CMakeLists.txt文件中添加:
①Boost所在package的依赖项
find_package(Boost REQUIRED COMPONENTS system thread)
②生成两个节点的可执行程序的命令:
cs_add_executable(example_action_server src/example_action_server.cpp)
cs_add_executable(example_action_client src/example_action_client.cpp)
最后进行编译就完成了
catkin_make
运行节点前,请确保已经运行了roscore
分别在两个不同的terminal中启动server和client:
rosrun example_action_server example_action_server
rosrun example_action_server example_action_client
在client的端口会有如下输出:
[ INFO] [1521442053.251384877]: doneCb: server responded with state [SUCCEEDED]
[ INFO] [1521442053.251542525]: got result output = 2242; goal_stamp = 2242; diff = 0
[ INFO] [1521442053.254128683]: doneCb: server responded with state [SUCCEEDED]
[ INFO] [1521442053.254174911]: got result output = 2243; goal_stamp = 2243; diff = 0
[ INFO] [1521442053.257378829]: doneCb: server responded with state [SUCCEEDED]
[ INFO] [1521442053.257444954]: got result output = 2244; goal_stamp = 2244; diff = 0
[ INFO] [1521442053.264676774]: doneCb: server responded with state [SUCCEEDED]
[ INFO] [1521442053.264862612]: got result output = 2245; goal_stamp = 2245; diff = 0
[ INFO] [1521442053.267605141]: doneCb: server responded with state [SUCCEEDED]
[ INFO] [1521442053.267730561]: got result output = 2246; goal_stamp = 2246; diff = 0
当节点运行后,可以查看当前有几个topic正在运行:
rostopic list
会有如下输出:
/example_action/cancel
/example_action/feedback
/example_action/goal
/example_action/result
/example_action/status
/rosout
/rosout_agg
可知有5个新的topic在example_action下被运行,可以通过查看命令观察它们输出:
例如查看goal的消息:
rostopic echo example_action/goal
会有如下输出:
---
header:
seq: 63929
stamp:
secs: 1521442598
nsecs: 441791983
frame_id: ''
goal_id:
stamp:
secs: 1521442598
nsecs: 441792381
id: /demo_action_client_node-63930-1521442598.441792381
goal:
input: 63930
---
header:
seq: 63930
stamp:
secs: 1521442598
nsecs: 443889821
frame_id: ''
goal_id:
stamp:
secs: 1521442598
nsecs: 443890098
id: /demo_action_client_node-63931-1521442598.443890098
goal:
input: 63931
在这个例程里面使用的“simple”action-server library 不能同时处理多个goals,也不能让它们排成队列,一个接一个处理,通俗地讲就是只有一个坑,被人占了就没地儿去了,所以选用action-server library时要考虑清楚想要的特性是什么。