在读move_base的代码的时候,遇到了actionlib,于是记录下学习笔记。
首先说,actionlib是一个完善service的功能包,当一个功能需要执行一段时间,但是你需要实时察看执行的状态和阶段的时候,service就无法满足了。
于是出现了actionlib。而actionlib中主要是由一个server和一个client的部分。
两个关系这样子的。
Actionlib 源码:
http://docs.ros.org/api/actionlib/html/namespaceactionlib.html
Actionlib的server和client部分符合这样的状态转移图。
Serve的状态转移图是这样的,
Server的方法记录如下:
而Client的状态转移图是这样的,
而client的所有方法记录在:
下面我们就写一个最简单的Actionlib的server和client,这里我们使用的是采用Goal返回函数。
首先我们还原官方例程使用的一个例子,洗盘子。而我们这个时候需要首先在包目录下加入action文件夹。在./action/DoDished.action文件中定义。
#goal definition
int32 samples
---
#result definition
float32 mean
float32 std_dev
---
#feedback
int32 sample
float32 data
float32 mean
float32 std_dev
下面在catkin_ws/src目录下创建一个测试package:
catkin_create_pkg actionlib_bing roscpp std_msgs actionlib actionlib_msgs message_generation rospy
在package的CMakeLists.txt文件中加入下面这几行:
#find_package(catkin REQUIRED genmsg actionlib_msgs actionlib) add_action_files(DIRECTORY action FILES DoDishes.action) generate_messages(DEPENDENCIES actionlib_msgs)
注意如果使用catkin_create_pkg创建包时没有添加actionlib相关的依赖项,要将上面CMakeLists中第一行的注释去掉,另外还要在package.xml文件中加入下面几行。因为我们在创建包时就添加好了相关依赖,所以这一步骤可以省略。
<build_depend>actionlib</build_depend> <build_depend>actionlib_msgs</build_depend> <run_depend>actionlib</run_depend> <run_depend>actionlib_msgs</run_depend>
使用catkin_make编译即可查看生成的消息文件,这些消息之后将会用于ActionClient 和 ActionServer间的通信。
另外可以看到,在devel/include/actionlib_test/中生成了相关的头文件:
C++ SimpleActionServer
我们首先要创建一个server,例程如下:
#include <actionlib_bing/DoDishesAction.h> #include <actionlib/server/simple_action_server.h> typedef actionlib::SimpleActionServer<actionlib_bing::DoDishesAction> Server; void execute(const actionlib_bing::DoDishesGoalConstPtr& goal, Server* as) { // Do lots of awesome groundbreaking robot stuff here ros::Duration(2).sleep(); as->setSucceeded(); } int main(int argc, char** argv) { ros::init(argc, argv, "do_dishes_server"); ros::NodeHandle n; Server server(n, "do_dishes", boost::bind(&execute, _1, &server), false); server.start(); ros::spin(); return 0; }
#include <actionlib_bing/DoDishesAction.h>
#include <actionlib/server/simple_action_server.h>
第一个就是引入DoDishes类的消息,而他的位置则是在你的devel/include/你的包的名字/中。
首先我们要定义一个SimpleActionServer,后面的则是消息类型。
typedef actionlib::SimpleActionServer<actionlib_bing::DoDishesAction> Server;
进入main函数。
主要的是server的构造,http://docs.ros.org/api/actionlib/html/classactionlib_1_1SimpleActionServer.html
server(n, "do_dishes", boost::bind(&execute, _1, &server), false);
其中的参数n,就是NodeHandle。而“do_dishes”,是你给server起的名字。boost::bind(&execute, _1, &server)是当收到新的goal时候需要的返回函数。其中boost::bind用法可以参见http://www.cnblogs.com/TIANHUAHUA/p/8418818.html。
我们的回调函数功能就是延时两秒后,发送完成信息。
server.start();开启server
一个简单的server就完成了。
C++ SimpleActionClient
我们简单改写一个Client,同样是基于官方例程。
#include <actionlib_bing/DoDishesAction.h> #include <actionlib/client/simple_action_client.h> typedef actionlib::SimpleActionClient<actionlib_bing::DoDishesAction> Client; int main(int argc, char** argv) { ros::init(argc, argv, "DoDishes_Client"); Client client("do_dishes", true); // true -> don‘t need ros::spin() client.waitForServer(); // Waits for the ActionServer to connect to this client actionlib_bing::DoDishesGoal goal; // Fill in goal here client.sendGoal(goal); // Sends a goal to the ActionServer client.waitForResult(ros::Duration(5.0)); // Blocks until this goal finishes ros::Rate loop_rate(1); while (ros::ok()){ // if (client.getState() == actionlib::SimpleClientGoalState::SUCCEEDED) // printf("Yay! The dishes are now clean\n"); printf("Current State: %s\n", client.getState().toString().c_str()); loop_rate.sleep(); }
typedef actionlib::SimpleActionClient<actionlib_bing::DoDishesAction> Client;
首先定义一个Client变量,
Client client("do_dishes", true);然后接入“do_dishes”的sever。True代表无需使用ros::spin(), 而false为需要自己添加ros::spin()。默认为true。
client需要发布goal之后,等待结果,最后就可以查询server的程序运行的当前状态了。
在CMakeLists文件中加入下面这几行:
add_executable(client src/client.cpp) add_executable(server src/server.cpp) target_link_libraries( client ${catkin_LIBRARIES}) target_link_libraries( server ${catkin_LIBRARIES})
首先运行server,在运行client
运行之后,我们会得到Active的等待goal完成,直到goal完成,状态变为succeeded。
C++ Move_base的client编写
#include <ros/ros.h> #include <actionlib/client/simple_action_client.h> #include <move_base_msgs/MoveBaseAction.h> #include <move_base_msgs/MoveBaseGoal.h> #include <geometry_msgs/PoseStamped.h> typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> Client; int main(int argc, char** argv) { ros::init(argc, argv, "move_base_actionlib_bing"); Client client("move_base", true); // true -> don‘t need ros::spin() client.waitForServer(); // Waits for the ActionServer to connect to this client // Fill in goal here (0.813, 2.349, 0.000) printf("Server connected. \r\n"); move_base_msgs::MoveBaseGoal action_goal; action_goal.target_pose.header.stamp = ros::Time::now(); action_goal.target_pose.header.frame_id = "map"; action_goal.target_pose.pose.position.x =0.813; action_goal.target_pose.pose.position.y =2.349; action_goal.target_pose.pose.position.z =0; action_goal.target_pose.pose.orientation.x =0; action_goal.target_pose.pose.orientation.y =0; action_goal.target_pose.pose.orientation.z =0; action_goal.target_pose.pose.orientation.w =1; client.sendGoal(action_goal); // Sends a goal to the ActionServer client.waitForResult(ros::Duration(05.0)); // Blocks until this goal finishes ros::Rate loop_rate(1); while (ros::ok()){ printf("Current State: %s\n", client.getState().toString().c_str()); loop_rate.sleep(); } return 0; }
其中,跑起来navigation的仿真包。我们再运行这个节点,就会通过move_base的server。
之后程序会发送一个目标点,我们一直打印着move_base运行状态。
注意,当我们不发送goal就直接读取返回状态的话,会出现
Trying to getState() when no goal is running. You are incorrectly using SimpleActionClient
并且返回Current State:LOST
参考资料:
Actionlib doc:
http://docs.ros.org/api/actionlib/html/classactionlib_1_1SimpleActionServer.html