SimpleActionServer端(C++)
SimpleActionServer端创建流程
1. 初始化ROS,创建节点
| ros::init(argc, argv, nodeName, ros::init_options::AnonymousName);
ros::NodeHandle node;
|
2. 创建Action的Server端
| actionlib::SimpleActionServer<demo_actions::CountNumberAction> server(node,actionName,boost::bind(&execute_callback, _1, &server),false);
server.start();
|
Tip
我们需要引入actionlib这个依赖库,添加头文件依赖
#include "actionlib/server/simple_action_server.h"
actionlib::SimpleActionServer: Action的Server端对应的类。
第一个参数Node: 表示当前的server端是基于这个node节点构建的
第二个参数:当前action的名称
第三个参数:是client端访问server端的回调
第四个参数:是否自动开启server
3. Server端的业务逻辑
server端的业务逻辑,主要是用于处理client请求的回调。用于结果反馈和过程反馈,提供简单示例:
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22 | void execute_callback1(const demo_actions::CountNumberGoalConstPtr &goal,
actionlib::SimpleActionServer<demo_actions::CountNumberAction> *server) {
ROS_INFO_STREAM("max: " << goal->max);
ROS_INFO_STREAM("duration: " << goal->duration);
//进度操作
ros::Rate rate(1.0 / goal->duration);
int count = 0;
while (count < goal->max) {
// 处理进度,反馈进度
demo_actions::CountNumberFeedback feedback;
feedback.percent = count * 100.0 / goal->max;
server->publishFeedback(feedback);
rate.sleep();
count++;
}
// 响应结果
demo_actions::CountNumberResult result;
result.count = count;
server->setSucceeded(result);
}
|
完整代码
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44 | #include "ros/ros.h"
#include "actionlib/server/simple_action_server.h"
#include <iostream>
#include "demo_actions/CountNumberAction.h"
using namespace std;
void execute_callback(const demo_actions::CountNumberGoalConstPtr &goal,
actionlib::SimpleActionServer<demo_actions::CountNumberAction> *server) {
ROS_INFO_STREAM("max: " << goal->max);
ROS_INFO_STREAM("duration: " << goal->duration);
//进度操作
ros::Rate rate(1.0 / goal->duration);
int count = 0;
while (count < goal->max) {
// 处理进度,反馈进度
demo_actions::CountNumberFeedback feedback;
feedback.percent = count * 100.0 / goal->max;
server->publishFeedback(feedback);
rate.sleep();
count++;
}
// 响应结果
demo_actions::CountNumberResult result;
result.count = count;
server->setSucceeded(result);
}
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
actionlib::SimpleActionServer<demo_actions::CountNumberAction> server(node, actionName,boost::bind(&execute_callback, _1,&server),false);
server.start();
//阻塞
ros::spin();
return 0;
}
|
Action实现原理
Action通讯机制,底层是通过Topic通讯机制去实现的。
Action通讯过程中,创建了5个Topic主题,通过5个topic进行数据的通讯,达到异步处理事件的结果。
- Goal Topic: 这个主题传递的数据是Goal指令。
client端
此时扮演的是Publisher
发布者,他主要的功能就是发布需求到这个主题。server端
此时扮演的是subscriber
订阅者,他主要的功能就是到这个主题中去获取需求。
- Cancel Toic:这个主题传递的是取消指令。
client端
此时扮演的是Publisher
发布者,他主要的功能就是发布取消命令到这个主题。server端
此时扮演的是subscriber
订阅者,他主要的功能就是到这个主题中去获取取消指令。
- Status Topic:这个主题传递的是当前任务执行的状态。
server端
此时扮演的是Publisher
发布者,他主要的功能就是发布当前任务执行的实时状态到这个主题。client端
此时扮演的是subscriber
订阅者,他主要的功能就是到这个主题中去获取执行的实时状态。
- Feedback Topic: 这个主题传递的是当前执行过程中的数据。
server端
此时扮演的是Publisher
发布者,他主要的功能就是发布当前任务执行过程中的数据到这个主题。client端
此时扮演的是subscriber
订阅者,他主要的功能就是到这个主题中去获取执行过程中的数据。
- Result Topic:这个主题传递的是当前执行结果数据。
server端
此时扮演的是Publisher
发布者,他主要的功能就是发布当前任务执行结果数据到这个主题。client端
此时扮演的是subscriber
订阅者,他主要的功能就是到这个主题中去获取执行结果数据。
调试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
1
2
3
4
5
6
7
8
9
10
11
12
13
14 | 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
|
client端接收到的Result反馈
| rosrun rqt_topic rqt_topic
|
client端发送Goal
| rosrun rqt_publisher rqt_publisher
|