action通信类似与服务通信,但于其不同的是在请求和响应中action通信可以实现实时且连续的反馈。
1.创建工作空间并编译
mkdir action_ws
cd action_ws
mkdir src
catkin_make
2.在src目录下新建功能包test,添加依赖roscpp rospy std_msgs actionlib actionlib_msgs
3.在功能包src目录下新建文件夹action,在其下新建文件AddInts.action并添加内容
#客户端输入目标值
int32 num
---
#服务端反馈结果
int32 result
---
#连续反馈进度值
float64 progress_bar
4.配置CMakeLists.txt文件
add_action_files(
FILES
AddInts.action
)
generate_messages(
DEPENDENCIES
actionlib_msgs
)
catkin_package(
CATKIN_DEPENDS actionlib actionlib_msgs roscpp rospy std_msgs
)
tips.此时可编译检验是否报错
5.配置c_cpp_properties.json文件,在includePath添加路径/xxx/yyy工作空间/devel/include/**
示例:
{
"configurations": [
{
"browse": {
"databaseFilename": "${default}",
"limitSymbolsToIncludedHeaders": false
},
"includePath": [
"/opt/ros/noetic/include/**",
//具体代码根据每个人计算机名称和功能包名称不同有所改变
"/home/sikero/action_ws/devel/include/**",
"/usr/include/**"
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "gnu11",
"cppStandard": "c++14"
}
],
"version": 4
}
6.在功能包src目录下新建服务端文件action_serve.cpp并配置CMakeLists.txt文件
#include "ros/ros.h"
#include "actionlib/server/simple_action_server.h"
#include "action_ws/AddIntsAction.h"
typedef actionlib::SimpleActionServer<action_ws::AddIntsAction> Server;
void cb(const action_ws::AddIntsGoalConstPtr &goal,Server* server){
//获取目标值
int num = goal->num;
ROS_INFO("目标值:%d",num);
//累加并响应连续反馈
int result = 0;
action_ws::AddIntsFeedback feedback;//连续反馈
ros::Rate rate(10);//通过频率设置休眠时间
for (int i = 1; i <= num; i++)
{
result += i;
//组织连续数据并发布
feedback.progress_bar = i / (double)num;
server->publishFeedback(feedback);
rate.sleep();
}
//设置最终结果
action_ws::AddIntsResult r;
r.result = result;
server->setSucceeded(r);
ROS_INFO("最终结果:%d",r.result);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ROS_INFO("action服务端实现");
// 2.初始化ROS节点;
ros::init(argc,argv,"AddInts_server");
// 3.创建NodeHandle;
ros::NodeHandle nh;
// 4.创建action服务对象;
/*SimpleActionServer(ros::NodeHandle n,
std::string name,
boost::function<void (const action_ws::AddIntsGoalConstPtr &)> execute_callback,
bool auto_start)
*/
// actionlib::SimpleActionServer<action_ws::AddIntsAction> server(....);
Server server(nh,"addInts",boost::bind(&cb,_1,&server),false);
server.start();
// 5.处理请求,产生反馈与响应;
// 6.spin().
ros::spin();
return 0;
}
配置CMakeLists.txt文件
add_executable(action_server src/action_server.cpp)
add_dependencies(action_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(action_server
${catkin_LIBRARIES}
)
//注意,此段代码必须添加在前文的catkin_package()之后,否则会报错
7.在功能包src目录下新建客户端文件action_client.cpp并配置CMakeLists.txt文件
#include "ros/ros.h"
#include "actionlib/client/simple_action_client.h"
#include "action_ws/AddIntsAction.h"
typedef actionlib::SimpleActionClient<action_ws::AddIntsAction> Client;
//处理最终结果
void done_cb(const actionlib::SimpleClientGoalState &state, const action_ws::AddIntsResultConstPtr &result){
if (state.state_ == state.SUCCEEDED)
{
ROS_INFO("最终结果:%d",result->result);
} else {
ROS_INFO("任务失败!");
}
}
//服务已经激活
void active_cb(){
ROS_INFO("服务已经被激活....");
}
//处理连续反馈
void feedback_cb(const action_ws::AddIntsFeedbackConstPtr &feedback){
ROS_INFO("当前进度:%.2f",feedback->progress_bar);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 2.初始化ROS节点;
ros::init(argc,argv,"AddInts_client");
// 3.创建NodeHandle;
ros::NodeHandle nh;
// 4.创建action客户端对象;
// SimpleActionClient(ros::NodeHandle & n, const std::string & name, bool spin_thread = true)
// actionlib::SimpleActionClient<action_ws::AddIntsAction> client(nh,"addInts");
Client client(nh,"addInts",true);
//等待服务启动
client.waitForServer();
// 5.发送目标,处理反馈以及最终结果;
/*
void sendGoal(const action_ws::AddIntsGoal &goal,
boost::function<void (const actionlib::SimpleClientGoalState &state, const action_ws::AddIntsResultConstPtr &result)> done_cb,
boost::function<void ()> active_cb,
boost::function<void (const action_ws::AddIntsFeedbackConstPtr &feedback)> feedback_cb)
*/
action_ws::AddIntsGoal goal;
goal.num = 10;
client.sendGoal(goal,&done_cb,&active_cb,&feedback_cb);
// 6.spin().
ros::spin();
return 0;
}
配置CMakeLists.txt文件
add_executable(action_client src/action_client.cpp)
add_dependencies(action_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(action_client
${catkin_LIBRARIES}
)
//注意,此段代码必须添加在前文的catkin_package()之后,否则会报错
8.在工作空间下编译一次,启动roscore,新开两个终端source后使用rosrun分别启动服务端和客户端文件,即可看到服务端接收到客户端传过来数据10,由服务端计算其累加结果并显示进度。