ActionServer端创建流程
1. 初始化ROS,创建节点
ros::init(argc, argv, nodeName, ros::init_options::AnonymousName);
ros::NodeHandle node;
2. 创建Action的Server端
actionlib::ActionServer<demo_actions::CountNumberAction> server(node,
actionName,
boost::bind(&goal_cb, _1),
boost::bind(&cancel_cb, _1),
false);
server.start();
我们需要引入actionlib这个依赖库,添加头文件依赖
#include "actionlib/server/action_server.h"
1
actionlib::ActionServer: Action的Server端对应的类。
第一个参数Node: 表示当前的server端是基于这个node节点构建的
第二个参数:当前action的名称
第三个参数:是client端访问server端的回调
第四个参数:是client取消执行操作,server端的回调
第五个参数:是否自动开启server
3. Server端的业务逻辑
server端的业务逻辑,主要是用于处理client请求的回调。用于结果反馈和过程反馈,提供简单示例:
void goal_cb(ServerGoalHandle goalHandle) {
ROS_INFO("goal_cb");
}
void cancel_cb(const ServerGoalHandle goalHandle) {
ROS_INFO("cancel_cb");
}
完整代码
#include "ros/ros.h"
#include "actionlib/server/action_server.h"
#include <iostream>
#include "demo_actions/CountNumberAction.h"
using namespace std;
typedef actionlib::ServerGoalHandle<demo_actions::CountNumberAction> ServerGoalHandle;
typedef actionlib::ActionServer<demo_actions::CountNumberAction> ActionServer;
void goal_cb(ServerGoalHandle goalHandle) {
ROS_INFO("goal_cb");
}
void cancel_cb(const ServerGoalHandle goalHandle) {
ROS_INFO("cancel_cb");
}
int main(int argc, char **argv) {
string nodeName = "CountNumberServer";
string actionName = "/count_number";
//创建节点
ros::init(argc, argv, nodeName, ros::init_options::AnonymousName);
ros::NodeHandle node;
//创建server
ActionServer server(node,
actionName,
boost::bind(&goal_cb, _1),
boost::bind(&cancel_cb, _1),
false);
server.start();
//阻塞
ros::spin();
return 0;
}
调试Server端
调试server端主要是查看server端是否能接收到请求,并根据请求数据处理相应的业务逻辑,然后返回处理好的结果。
在这里,我们只需要模拟client端发送请求就可以了。
在这里,我们需要模拟以下情况:
- client端发送Goal
- client端接收到的Feedback反馈
- client端接收到的Result反馈
ROS提供了命令行工具和图形化工具供我们调试开发。
1. 通过ros命令进行调试
client端接收到的Feedback反馈
rosttopic echo /count_number/feedback
client端接收到的Result反馈
rostopic echo /count_number/result
client端发送Goal
rostopic pub /count_number/goal demo_actions/CountNumberActionGoal "header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
goal_id:
stamp:
secs: 0
nsecs: 0
id: ''
goal:
max: 1000
duration: 0.1"
2. 通过rqt工具进行调试
client端接收到的Feedback反馈
rosrun rqt_topic rqt_topic

图片.png
client端接收到的Result反馈
rosrun rqt_topic rqt_topic

图片.png
client端发送Goal
rosrun rqt_publisher rqt_publisher
[图片上传失败...(image-aa341c-1564107600863)]