在ROS中除了常见的话题(topic)通信、服务(server)通信等方式,还有action通信这一方式,由于可以实时反馈任务完成情况,该通信方式被广泛运用于机器人导航等任务中。本文将通过三个小节的分享,实现基于action通信的阶乘运算。
第一节:自定义action文件
第二节:基于C++实现action通信的服务端
第三节:基于C++实现action通信的客户端
本节为第二节:基于C++实现action通信的服务端
详细步骤如下:
步骤1:在action_ws/src/factorial_pkg/src下创建factorial_server.cpp文件
cpp
cd action_ws/src/factorial_pkg/src
touch factorial_server.cpp
步骤2: 编写factorial_server.cpp文件
作者已在代码中进行了详细注释
cpp
#include "ros/ros.h"
// 创建一个简单行为服务器(simple_action_server)
#include "actionlib/server/simple_action_server.h"
// 导入自定义action文件
#include "factorial_pkg/FactorialAction.h"
/* 由于 actionlib::SimpleActionServer<factorial_pkg::FactorialAction>
名称太长,使用typedef给它一个简短的命名 */
typedef actionlib::SimpleActionServer<factorial_pkg::FactorialAction> as;
// 定义FactorialAction类,阶乘运算将在这个类内实现
class FactorialAction
{
protected:
ros::NodeHandle nh_; // ros句柄
as as_; // 定义行为服务器 as_
// action通信的话题名称(类似于话题通信中的topic name)
std::string action_name_;
// 定义action中的结果与反馈变量
factorial_pkg::FactorialResult result_;
factorial_pkg::FactorialFeedback feedback_;
public:
// 构造函数(使用参数列表进行参数初始化)
FactorialAction(std::string name):
/*
as_的第一个参数是NodeHandle的名称
第二个参数是action通信的话题名称
第三个参数用于将回调函数与当前的对象进行绑定<个人想法:理解不了就背一下(反正作者是背的Hhh...)>
第四个参数用于选择是否自动启动
如果是false,需要as_.start()启动
如果true,则不需要改行代码
注意, as_()内的参数位置不能改变
*/
as_(nh_, name, boost::bind(&FactorialAction::executeCB, this, _1), false),
action_name_(name)
{
as_.start();
}
~FactorialAction(){}
/*
回调函数的实现
1 需要定义频率 ros::Rate r(10),主要是feedback需要使用
2 具体实现阶乘
*/
void executeCB(const factorial_pkg::FactorialGoalConstPtr &goal)
{
ros::Rate r(10);
bool success = true;
// 获取goal -> goal
int64_t g = goal->goal;
// 实现阶乘
int64_t result = 1;
for(int i=1; i<=g; i++)
{
// 检查进程是否需要关闭
if(as_.isPreemptRequested() || !ros::ok())
{
as_.setPreempted();
success = false;
break;
}
result = result * i;
feedback_.feedback_num = i / (double)g;
// 发送feedback
as_.publishFeedback(feedback_);
r.sleep();
}
if(success)
{
result_.result = result;
ROS_INFO("%s: Succeeded", action_name_.c_str());
// 发送feedback
as_.setSucceeded(result_);
}
}
};
int main(int argc, char *argv[])
{
ros::init(argc, argv, "factorial_server");
// 实例化一个对象,传入行为服务器话题名称
FactorialAction factorial_action("factorial_action");
ros::spin();
return 0;
}
步骤3:编写factorial_pkg下的CMakeLists.txt文件
cpp
add_executable(factorial_server src/factorial_server.cpp)
target_link_libraries(factorial_server ${catkin_LIBRARIES})
步骤4:检查是否成功创建simple_action_server
启动roscore,
新打开一个终端运行factorial_server节点,
与此同时,再新打开一个终端执行rostopic list -v
如果没有问题会有如下效果
cpp
a@melodic:~/desk/action_ws$ rostopic list -v
Published topics:
* /factorial_action/result [factorial_pkg/FactorialActionResult] 1 publisher
* /rosout [rosgraph_msgs/Log] 1 publisher
* /factorial_action/status [actionlib_msgs/GoalStatusArray] 1 publisher
* /rosout_agg [rosgraph_msgs/Log] 1 publisher
* /factorial_action/feedback [factorial_pkg/FactorialActionFeedback] 1 publisher
Subscribed topics:
* /rosout [rosgraph_msgs/Log] 1 subscriber
* /factorial_action/cancel [actionlib_msgs/GoalID] 1 subscriber
* /factorial_action/goal [factorial_pkg/FactorialActionGoal] 1 subscriber
a@melodic:~/desk/action_ws$ catkin_create_pkg