ROS有消息机制,也有服务机制。一个同步的通讯机制,一个异步的通讯机制。服务机制在要求异步而且响应时间不定的场景下有先天的劣势,如果服务端迟迟没有响应,那么客户端程序将处于阻塞状态,直到超时。这会使操作变得相当耗时,因此action消息类型的出现主要解决此类问题。
一、自定义一个action
在action文件夹下创建一个以.action 结尾的消息类型,消息类型主要由三部分组成:目标,结果和反馈
#part1: the goal, to be sent by the client
---
#part2: the result, to be sent by the server upon completion
---
#part3: the feedback, to be sent by server during execution
例如在项目中定义action消息如下
int32 goal_num
---
bool finsh
---
float32 complete_percent
二、工程文件撰写
在CMakeLists.txt 文件中添加actionlib 和actionlib_msgs依赖,add_action_files添加自定义的action文件, generate_messages添加自定义文件的依赖包,同时增加客户端和服务端的编译
cmake_minimum_required(VERSION 3.0.2)
project(DoDishes)
add_compile_options(-std=c++11)
find_package(catkin REQUIRED COMPONENTS
actionlib
actionlib_msgs
std_msgs
roscpp
rospy
)
add_action_files(DIRECTORY action FILES DoDishes.action)
generate_messages(DEPENDENCIES std_msgs actionlib_msgs)
catkin_package(
CATKIN_DEPENDS roscpp rospy std_msgs
)
include_directories(
include
${catkin_INCLUDE_DIRS}
)
add_executable(DoDishes_client src/DoDishes_client.cpp)
target_link_libraries( DoDishes_client ${catkin_LIBRARIES})
add_dependencies(DoDishes_client ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_executable(DoDishes_server src/DoDishes_server.cpp)
target_link_libraries( DoDishes_server ${catkin_LIBRARIES})
add_dependencies(DoDishes_server ${${PROJECT_NAME}_EXPORTED_TARGETS})
package.xml文件中增加相关依赖
<?xml version="1.0"?>
<package format="2">
<name>DoDishes</name>
<version>0.0.0</version>
<description>The DoDishes package</description>
<maintainer email="wei@todo.todo">wei</maintainer>
<license>TODO</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>actionlib</build_export_depend>
<build_export_depend>actionlib_msgs</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<export>
</export>
</package>
三、 coding
3.1 客户端代码编写,此处命名为DoDishes_client.cpp文件
#include <actionlib/client/simple_action_client.h>
#include "action_test/DoDishesAction.h" //自定义消息头文件
typedef actionlib::SimpleActionClient<action_test::DoDishesAction> Client;
// 当action完成后会调用该回调函数一次
void doneCb(const actionlib::SimpleClientGoalState& state,
const action_test::DoDishesResultConstPtr& result) {
ROS_INFO("Yay! The dishes are now clean");
ros::shutdown();
}
// 当action激活后会调用该回调函数一次
void activeCb() { ROS_INFO("Goal just went active"); }
// 收到feedback后调用该回调函数
void feedbackCb(const action_test::DoDishesFeedbackConstPtr& feedback) {
ROS_INFO(" percent_complete : %f ", feedback->percent_complete);
}
int main(int argc, char** argv) {
ros::init(argc, argv, "do_dishes_client");
// 定义一个客户端
Client client("do_dishes", true);
// 等待服务器端
ROS_INFO("Waiting for action server to start.");
client.waitForServer();
ROS_INFO("Action server started, sending goal.");
// 创建一个action的goal
action_test::DoDishesGoal goal;
goal.dishwasher_id = 1;
// 发送action的goal给服务器端,并且设置回调函数
client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
ros::spin();
return 0;
}
3.2 服务端代码编写
此处创建一个DoDishes_server.cpp文件
#include <actionlib/server/simple_action_server.h>
#include <ros/ros.h>
#include "action_test/DoDishesAction.h"
typedef actionlib::SimpleActionServer<action_test::DoDishesAction> Server;
// 收到action的goal后调用该回调函数
void execute(const action_test::DoDishesGoalConstPtr& goal, Server* as) {
ros::Rate r(1); // 设置运行效率1Hz
action_test::DoDishesFeedback feedback; // 创建一个反馈对象
ROS_INFO("Dishwasher %d is working.", goal->dishwasher_id);
// 假设洗盘子的进度,并且按照1hz的频率发布进度feedback
for (int i = 1; i <= 10; i++) {
feedback.percent_complete = i * 10;
as->publishFeedback(feedback);
r.sleep();
}
// 当action完成后,向客户端返回结果
ROS_INFO("Dishwasher %d finish working.", goal->dishwasher_id);
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;
}
四、创建客户端和服务端的launch文件
action_client.launch
<?xml version="1.0"?>
<launch>
<node pkg="DoDishes" type="DoDishes_client" name="DoDishes_client" output="screen" >
</node>
</launch>
action_server.launch
<?xml version="1.0"?>
<launch>
<node pkg="DoDishes" type="DoDishes_server" name="DoDishes_server" output="screen" >
</node>
</launch>
五、运行
客户端输出
服务端输出
Enjoy!