actionlib


actionlib

前言

  • Actionlib是ROS中一个很重要的库,类似service通信机制,actionlib也是一种请求响应机制的通信方式,actionlib主要弥补了service通信的一个不足,就是当机器人执行一个长时间的任务时,假如利用service通信方式,那么publisher会很长时间接受不到反馈的reply,致使通信受阻。当service通信不能很好的完成任务时候,actionlib则可以比较适合实现长时间的通信过程,actionlib通信过程可以随时被查看过程进度,也可以终止请求,这样的一个特性,使得它在一些特别的机制中拥有很高的效率

简介

  • 那么什么是 action?
    • 一种问答通信机制
    • 带有连续的反馈
    • 可以在任务过程中止运行
    • 基于ROS的消息机制实现
    • 多对多的action-server与action-client的交互机制

客户端-服务器交互

  • actionlib 使用 client-server工作模式,ActionClient 和 ActionServer 通过 "ROS Action Protocol" 进行通信,"ROS Action Protocol" 以 ROS 消息方式进行传输。此外 ActionClient 和 ActionServer 为用户提供了一些简单的接口,用户使用这些接口可以完成 goal 请求(client-side)和 goal 执行(server-side)

client_server_interaction.png

  • ActionClient 和 ActionServer 之间使用action protocol通信,action protocol 就是预定义的一组 ROS message,这些 message 被放到 ROS topic 上在 ActionClient 和 ActionServer 之间进行传输实现二者的沟通

action_interface.png

ROS Message:

  • goal:用于向服务器发送任务目标
  • cancel:用于向服务器发送取消请求
  • status:用于通知客户端系统中每个目标的当前状态
  • feedback:用于周期反馈任务运行的监控数据
  • result:用于向client发送任务的执行结果,这个topic只会发布一次

创建action功能包

  • 依然使用 catkin_simple 功能来创建 package
catkin_create_pkg dodishes roscpp actionlib actionlib_msgs
  • 然后在新建的package中创建一个action文件夹用来存储action messages的信息,方法与创建service messages一样
cd dodishes
mkdir action
  • 惯例,在package.xml文件中添加两行生成消息文件的语句
  message_generation
  message_runtime

定义action文件

  • ROS系统在action文件(文件名后缀为.action)中定义了上述 goal、result、feedback 等消息,每部分用 “---” 分隔
  • 这些文件被放置在包的 ./action 目录

例如:./action/DoDishes.action

./action/DoDishes.action # 定义目标消息
# Define the goal
uint32 dishwasher_id  # Specify which dishwasher we want to use
---
# Define the result # 定义结果消息
uint32 total_dishes_cleaned
---
# Define a feedback message # 定义周期反馈消息
float32 percent_complete

基于这个 .action 文件,需要生成 6 条消息,以便客户端和服务器进行通信

功能包配置

package.xml

  • 在package.xml文件中添加以下几行
actionlib
actionlib_msgs
actionlib
actionlib_msgs

CMakeLists.txt

  • 在CMakeLists.txt文件中添加以下几行
find_package(catkin REQUIRED COMPONENTS
	actionlib_msgs
	actionlib
)

add_action_files(DIRECTORY action
	FILES
	DoDishes.action
)

generate_messages(
	DEPENDENCIES
	actionlib_msgs
)

catkin_package(
	CATKIN_DEPENDS actionlib_msgs
)

编写action_server

  • 在dodishes/src中创建DoDishes_server.cpp文件
#include 
#include   // 这是一个library里面一个做好的包(simple_action_server)里面的头文件
#include "dodishes/DoDishesAction.h"  // 这个头文件是重点,在上一部分生成的action消息的头文件

// 为服务端数据类型定义别名
typedef actionlib::SimpleActionServer Server;

// 收到action的goal后调用该回调函数
void execute(const dodishes::DoDishesGoalConstPtr & goal, Server * as)
{
    ros::Rate r(1);
    dodishes::DoDishesFeedback feedback;

    ROS_INFO("Dishwasher %d is working.", goal->dishwasher_id);

    // 假设洗盘子的进度,并且按照1hz的频率发布进度feedback
    for (int i = 1; i <= 10; i++)
    {
        feedback.percent_complete = i * 10;

	// 发布feedback
        as->publishFeedback(feedback);

        r.sleep();
    }

    // 当action完成后,向客户端返回结果
    ROS_INFO("Dishwasher %d finish working.", goal->dishwasher_id);
    as->setSucceeded();
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "do_dishes_server");
    ros::NodeHandle n;

    // 定义一个服务器
    Server server(n, "do_dishes", boost::bind(&execute, _1, &server), false);
    // 其中的参数n,就是NodeHandle。而“do_dishes”,是你给server起的名字
    // boost::bind(&execute, _1, &server)是当收到新的goal时候需要的返回函数
    // false的意思是暂时不启动这个server
    
    server.start();  // 服务器开始运行

    ros::spin();

    return 0;
}

总结:

  • 初始化ROS节点;
  • 创建action_server实例;
  • 启动服务器,等待action请求;
  • 在回调函数中完成动作服务功能的处理,并反馈进度信息;
  • action完成,发送结束信息

编写action_client

  • 在dodishes/src中创建DoDishes_client.cpp文件
#include 
#include   // 这是一个library里面一个做好的包(simple_action_server)里面的头文件
#include "dodishes/DoDishesAction.h"  // 这个头文件是重点,在上一部分生成的action消息的头文件

// 为客户端数据类型定义一个别名
typedef actionlib::SimpleActionClient Client;

// 当服务器完成后会调用该回调函数一次
void doneCb(const actionlib::SimpleClientGoalState & state,
            const dodishes::DoDishesResultConstPtr & result)
{
    ROS_INFO("Yay! The dishes are now clean");
    ros::shutdown();
}

// 当服务器激活后会调用该回调函数一次
void activeCb()
{
    ROS_INFO("Goal just went active");
}

// 收到feedback后调用该回调函数
void feedbackCb(const dodishes::DoDishesFeedbackConstPtr & feedback)
{
    ROS_INFO(" percent_complete : %f ", feedback->percent_complete);
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "do_dishes_client");

    // 定义一个客户端,连接名为do_dishes的服务器,开启自循环线程
    Client client("do_dishes", true);

    ROS_INFO("Waiting for action server to start.");

    client.waitForServer();  // 客户端等待服务器函数
    // 可以传递一个ros::Duration作为最大等待值,程序进入到这个函数开始挂起等待
    // 服务器就位或者达到等待最大时间退出,前者返回true,后者返回false

    ROS_INFO("Action server started, sending goal.");

    dodishes::DoDishesGoal goal;  // 创建一个action的goal

    goal.dishwasher_id = 1;  // 定义盘子的目标,也就是洗一个盘子

    // 发送action的goal给服务器端,并且设置回调函数
    client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);

    ros::spin();

    return 0;
}

总结:

  • 初始化ROS节点;
  • 创建action_client实例;
  • 连接action服务端;
  • 发送action goal;
  • 根据不同类型的服务端反馈处理回调函数

编译配置

CMakeLists.txt

add_executable(DoDishes_client src/DoDishes_client.cpp)  
target_link_libraries( DoDishes_client ${catkin_LIBRARIES})
add_dependencies(DoDishes_client ${${PROJECT_NAME}_EXPORTED_TARGETS})

add_executable(DoDishes_server src/DoDishes_server.cpp)  
target_link_libraries( DoDishes_server ${catkin_LIBRARIES})
add_dependencies(DoDishes_server ${${PROJECT_NAME}_EXPORTED_TARGETS})
ROS