ROS入门 10.1.2 action通信自定义action文件调用A(C++)
《ROS入门-理论与实践》视频教程镇楼
需求:
创建两个ROS 节点,服务器和客户端,客户端可以向服务器发送目标数据N(一个整型数据)服务器会计算 1 到 N 之间所有整数的和,这是一个循环累加的过程,返回给客户端,这是基于请求响应模式的,又已知服务器从接收到请求到产生响应是一个耗时操作,每累加一次耗时0.1s,为了良好的用户体验,需要服务器在计算过程中,每累加一次,就给客户端响应一次百分比格式的执行进度,使用 action实现。
流程:
- 编写action服务端实现;
- 编写action客户端实现;
- 编辑CMakeLists.txt;
- 编译并执行。
0.vscode配置
需要像之前自定义 msg 实现一样配置c_cpp_properies.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置,配置方式与之前相同:
{
"configurations": [
{
"browse": {
"databaseFilename": "",
"limitSymbolsToIncludedHeaders": true
},
"includePath": [
"/opt/ros/noetic/include/**",
"/usr/include/**",
"/xxx/yyy工作空间/devel/include/**" //配置 head 文件的路径
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "c11",
"cppStandard": "c++17"
}
],
"version": 4
}
1.服务端
#include "ros/ros.h"
#include "actionlib/server/simple_action_server.h"
#include "demo01_action/AddIntsAction.h"
/*
需求:
创建两个ROS节点,服务器和客户端,
客户端可以向服务器发送目标数据N(一个整型数据)
服务器会计算1到N之间所有整数的和,这是一个循环累加的过程,返回给客户端,
这是基于请求响应模式的,
又已知服务器从接收到请求到产生响应是一个耗时操作,每累加一次耗时0.1s,
为了良好的用户体验,需要服务器在计算过程中,
每累加一次,就给客户端响应一次百分比格式的执行进度,使用action实现。
流程:
1.包含头文件;
2.初始化ROS节点;
3.创建NodeHandle;
4.创建action服务对象;
5.处理请求,产生反馈与响应;
6.spin().
*/
typedef actionlib::SimpleActionServer<demo01_action::AddIntsAction> Server;
void cb(const demo01_action::AddIntsGoalConstPtr &goal,Server* server){
//获取目标值
int num = goal->num;
ROS_INFO("目标值:%d",num);
//累加并响应连续反馈
int result = 0;
demo01_action::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();
}
//设置最终结果
demo01_action::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 demo01_action::AddIntsGoalConstPtr &)> execute_callback,
bool auto_start)
*/
// actionlib::SimpleActionServer<demo01_action::AddIntsAction> server(....);
Server server(nh,"addInts",boost::bind(&cb,_1,&server),false);
server.start();
// 5.处理请求,产生反馈与响应;
// 6.spin().
ros::spin();
return 0;
}
PS:
可以先配置CMakeLists.tx文件并启动上述action服务端,然后通过 rostopic 查看话题,向action相关话题发送消息,或订阅action相关话题的消息。
2.客户端
#include "ros/ros.h"
#include "actionlib/client/simple_action_client.h"
#include "demo01_action/AddIntsAction.h"
/*
需求:
创建两个ROS节点,服务器和客户端,
客户端可以向服务器发送目标数据N(一个整型数据)
服务器会计算1到N之间所有整数的和,这是一个循环累加的过程,返回给客户端,
这是基于请求响应模式的,
又已知服务器从接收到请求到产生响应是一个耗时操作,每累加一次耗时0.1s,
为了良好的用户体验,需要服务器在计算过程中,
每累加一次,就给客户端响应一次百分比格式的执行进度,使用action实现。
流程:
1.包含头文件;
2.初始化ROS节点;
3.创建NodeHandle;
4.创建action客户端对象;
5.发送目标,处理反馈以及最终结果;
6.spin().
*/
typedef actionlib::SimpleActionClient<demo01_action::AddIntsAction> Client;
//处理最终结果
void done_cb(const actionlib::SimpleClientGoalState &state, const demo01_action::AddIntsResultConstPtr &result){
if (state.state_ == state.SUCCEEDED)
{
ROS_INFO("最终结果:%d",result->result);
} else {
ROS_INFO("任务失败!");
}
}
//服务已经激活
void active_cb(){
ROS_INFO("服务已经被激活....");
}
//处理连续反馈
void feedback_cb(const demo01_action::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<demo01_action::AddIntsAction> client(nh,"addInts");
Client client(nh,"addInts",true);
//等待服务启动
client.waitForServer();
// 5.发送目标,处理反馈以及最终结果;
/*
void sendGoal(const demo01_action::AddIntsGoal &goal,
boost::function<void (const actionlib::SimpleClientGoalState &state, const demo01_action::AddIntsResultConstPtr &result)> done_cb,
boost::function<void ()> active_cb,
boost::function<void (const demo01_action::AddIntsFeedbackConstPtr &feedback)> feedback_cb)
*/
demo01_action::AddIntsGoal goal;
goal.num = 10;
client.sendGoal(goal,&done_cb,&active_cb,&feedback_cb);
// 6.spin().
ros::spin();
return 0;
}
PS:等待服务启动,只可以使用client.waitForServer();
,之前服务中等待启动的另一种方式ros::service::waitForService("addInts");
不适用
3.编译配置文件
add_executable(action01_server src/action01_server.cpp)
add_executable(action02_client src/action02_client.cpp)
...
add_dependencies(action01_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(action02_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
...
target_link_libraries(action01_server
${catkin_LIBRARIES}
)
target_link_libraries(action02_client
${catkin_LIBRARIES}
)
4.执行
首先启动 roscore,然后分别启动action服务端与action客户端,最终运行结果与案例类似。