ActionClient端实现(C++)

ActionClient创建流程

1. 创建Node节点

1
2
ros::init(argc, argv, nodeName, ros::init_options::AnonymousName);
ros::NodeHandle node;

2. 创建SimpleActionClient

Tip

我们需要引入actionlib这个依赖库,添加头文件依赖

#include "actionlib/client/action_client.h"

actionlib::ActionClient: Action的Client端对应的类。

第一个参数Node: 表示当前的client端是基于这个node节点构建的

第二个参数:当前action的名称

3. 发送Goal指令给Server端

1
2
3
4
5
6
7
demo_actions::CountNumberGoal goal;
goal.max = 100;
goal.duration = 0.5;
client.sendGoal(
            goal,
            boost::bind(&transition_cb, _1),
            boost::bind(&feedback_cb, _1, _2));

Tip

GoalHandle sendGoal(const Goal & goal, TransitionCallback transition_cb = TransitionCallback(), FeedbackCallback feedback_cb = FeedbackCallback())

sendGoal函数,对应了几个参数。

第一个参数goal: 对应的是发送的指令数据,server端会根据客户端的数据进行对应的逻辑。

第二个参数transition_cb:server端状态改变时,告知客户端的回调。

第三个参数feedback_cb: server端在执行操作过程中,告知客户端的进度回调。

4.完成回调

状态回调

1
2
3
void transition_cb(ClientGoalHandle goalHandle) {
    ROS_INFO("========= transition_cb =========");
}

进度回调

1
2
3
4
void feedback_cb(ClientGoalHandle goalHandle,
                 const demo_actions::CountNumberFeedbackConstPtr feedback) {
    ROS_INFO("========= feedback_cb =========");
}

完整代码

 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
45
46
#include "ros/ros.h"
#include <iostream>
#include "actionlib/client/action_client.h"
#include "actionlib/client/terminal_state.h"
#include "demo_actions/CountNumberAction.h"

typedef actionlib::ClientGoalHandle<demo_actions::CountNumberAction> ClientGoalHandle;
typedef demo_actions::CountNumberFeedbackConstPtr FeedbackConstPtr;
typedef demo_actions::CountNumberResultConstPtr ResultConstPtr;
typedef actionlib::ActionClient<demo_actions::CountNumberAction> ActionClient;

using namespace std;

void transition_cb(ClientGoalHandle goalHandle) {
    ROS_INFO("========= transition_cb =========");
}

void feedback_cb(ClientGoalHandle goalHandle,
                 const FeedbackConstPtr feedback) {
    ROS_INFO("========= feedback_cb =========");
}

int main(int argc, char **argv) {
    string nodeName = "CountNumberClient";
    string actionName = "/count_number";

    // 创建节点
    ros::init(argc, argv, nodeName, ros::init_options::AnonymousName);
    ros::NodeHandle node;

    // 创建client
    ActionClient client(node, actionName);
    client.waitForActionServerToStart();

    // 发送
    demo_actions::CountNumberGoal goal;
    goal.max = 100;
    goal.duration = 0.5;
    client.sendGoal(
            goal,
            boost::bind(&transition_cb, _1),
            boost::bind(&feedback_cb, _1, _2));
    // 阻塞线程
    ros::spin()
    return 0;
}

调试Client端

通过现有的server端进行调试。