系列文章目录
留空
文章目录
前言
自用
一、题目
在ROS中,动作是一种特殊的通信机制,用于处理那些需要长时间运行、可能需要中途反馈并且可能会被取消的任务。
动作的组成部分
目标(Goal):
客户端向服务器发送一个请求,指明希望执行的具体任务。
服务器接收并确认该目标,开始执行任务。
反馈(Feedback):
服务器在执行任务过程中定期发布当前任务的进度或中间结果。
客户端可以订阅这些反馈消息,以了解任务的实时状态。
结果(Result):
服务器完成任务后发布最终结果。
客户端接收结果,并根据需要执行后续操作。
不难看出,动作就是由两个服务和一个话题组合而成。
- 动作客户端通过“目标服务”给动作服务端发送“目标”,动作服务端根据情况返回响应(接受/不接受)。
- 在执行过程中,动作服务端在“反馈话题”中发布任务进度,客户端可以订阅此话题,接收这些反馈消息。
- 动作客户端通过“结果服务”给动作服务端发送“询问”,动作服务端根据情况返回响应(已取消/已完成)。
进入正题:
在这个动作中,赵六充当写稿作者(服务端),而孙七作为编辑则是催稿人(客户端)。
首先,孙七通过“写稿目标”服务向赵六发送写稿任务。赵六接收到任务后,会判断任务是否要求写五章。如果任务恰好是五章,赵六会接受任务;如果不是五章,赵六则会拒绝任务。
一旦赵六接受了写稿任务,他开始写作,并且每五秒钟完成一章。在写作过程中,赵六会不断向孙七反馈他的写作进度和内容。
当赵六写完五章后,他会通知孙七,告知任务已经完成。
然而,在赵六进行写作的过程中,如果孙七发送了取消写稿的指令,赵六会根据情况做出反应。如果已经写了超过三章,赵六会拒绝停止写作。此外,在写作过程中,赵六也不会接受第二次安排的写稿任务。
总结一下,
孙七(催稿人,客户端)的动作流程:
孙七使用“写稿目标”服务向赵六发送写稿任务,指定需要写的章节数量。
在赵六写作期间,孙七可以实时接收赵六的写作进度和内容反馈。
如果孙七需要取消当前的写稿任务,根据赵六的反馈判断是否取消成功。
赵六(写稿作者,服务端)的动作流程:
赵六接收来自孙七的写稿任务,并判断任务要求是否为五章。如果是五章,赵六接受任务并开始写作。
赵六按照每五秒一章的速度进行写作,并将写作进度和内容实时反馈给孙七。
赵六在完成五章后,通知孙七写作任务已经完成。
如果在写作过程中收到孙七的取消指令,赵六会根据自己的写作进度决定是否停止。如果已写章节超过三章,则继续完成剩余章节。
在写作过程中,赵六不接受新的写稿任务安排。
二、创建动作自定义接口
这里简写了,具体可以参考ROS2 + C++ 自定义接口(自用笔记)
1.编写自定义接口
根据题目,我们创建一个自定义接口功能包。
cd towm_ws/src
ros2 pkg create learning_interfaces2 --build-type ament_cmake --dependencies rclcpp
在src
下创建action
文件夹,在文件夹下创建ContractWriter.action
文件。
#动作自定义接口
#目标
uint32 write_goal
---
#结果
bool finish
---
#反馈
uint32 chapter_num
string[] chapter_content
uint32 write_goal
写稿目标
bool finish
写稿完成情况(是or否)
chapter_num
写稿数量进度
chapter_content
写稿的内容
每次编写完代码记得修改CmakeLists.txt
和package.xml
,添加以下代码
CmakeLists.txt
find_package(rosidl_default_generators REQUIRED)
#添加消息文件和依赖
rosidl_generate_interfaces(${PROJECT_NAME}
"action/ContractWriter.action"
)
package.xml
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
2.编译
输入命令行
colcon build --packages-select learning_interfaces2
查看一下接口是否创建成功
source install/setup.sh
ros2 interface package learning_interfaces2
到这,我们就完成了自定义动作接口的创建啦!
三、创建功能包和节点
(1)创建功能包
注意!我们这次多加了一个rclcpp_action
的依赖项。
cd towm_ws/src
ros2 pkg create learning_action --build-type ament_cmake --dependencies rclcpp rclcpp_action
(2)创建孙七和赵六节点
四、使用RCLCPP编写话题
1.基础代码
(1)作家赵六节点
/* 编写动作服务端*/
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
class Writers : public rclcpp::Node
{
public:
Writers(std::string name) : Node(name)
{
RCLCPP_INFO(this->get_logger(),"作家节点%s已启动",name.c_str());
}
private:
};
int main(int argc,char** argv)
{
rclcpp::init(argc,argv);
auto node = std::make_shared<Writers>("zhao6");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
(2)编辑孙七节点
/* 编写动作客户端*/
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
class Editors : public rclcpp::Node
{
public:
Editors(std::string name) : Node(name)
{
RCLCPP_INFO(this->get_logger(),"编辑节点%s已启动",name.c_str());
}
private:
};
int main(int argc,char** argv)
{
rclcpp::init(argc,argv);
auto node = std::make_shared<Editors>("sun7");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
每次编写完代码记得修改CmakeLists.txt
和package.xml
,添加依赖rclcpp_action
和learning_interfaces2
CmakeLists.txt
add_executable(zhao6_node src/zhao6.cpp)
ament_target_dependencies(zhao6_node rclcpp rclcpp_action learning_interfaces2)
add_executable(sun7_node src/sun7.cpp)
ament_target_dependencies(sun7_node rclcpp rclcpp_action learning_interfaces2)
install(TARGETS
zhao6_node
sun7_node
DESTINATION lib/${PROJECT_NAME}
)
package.xml
<depend>rclcpp_action</depend>
<depend>learning_interfaces2</depend>
最后编译测试一下
打开一个终端
colcon build --packages-select learning_action
source install/setup.sh
ros2 run learning_action sun7_node
打开另一个终端
source install/setup.sh
ros2 run learning_action zhao6_node
2.编写“催稿”动作服务端赵六
完整代码
zhao6.cpp
/* 编写动作服务端*/
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
// (1)导入服务接口
#include "learning_interfaces2/action/contract_writer.hpp"
class Writers : public rclcpp::Node
{
public:
Writers(std::string name) : Node(name)
{
RCLCPP_INFO(this->get_logger(),"作家节点%s已启动",name.c_str());
using namespace std::placeholders;
//(7)创建动作服务端
this->action_Writer = rclcpp_action::create_server<learning_interfaces2::action::ContractWriter>(
this,
"contract",
std::bind(&Writers::handle_writergoal, this, _1, _2),
std::bind(&Writers::handle_writercancel, this, _1),
std::bind(&Writers::handle_writeraccepted, this, _1));
}
private:
//(2)声明动作服务端
rclcpp_action::Server<learning_interfaces2::action::ContractWriter>::SharedPtr action_Writer;
int chapters = 0; //已完成的章节数
bool writing_in_progress = false; //是否正在写作
bool stop_writing = false;
//(3)创建处理目标函数(handle_goal)
rclcpp_action::GoalResponse handle_writergoal(const rclcpp_action::GoalUUID& BookID,
std::shared_ptr<const learning_interfaces2::action::ContractWriter::Goal> goal)
{
//(8)编写处理目标函数
RCLCPP_INFO(this->get_logger(),"已收到编辑部的催稿%d章",goal->write_goal);
(void)BookID;
if( (goal->write_goal) == 5 && writing_in_progress == false )
{
RCLCPP_INFO(this->get_logger(),"接受催稿");
writing_in_progress = true; //进入写作状态
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}
else
{
RCLCPP_INFO(this->get_logger(),"拒绝催稿");
return rclcpp_action::GoalResponse::REJECT;
}
}
//(4)创建处理接受目标函数(handle_accepted)
void handle_writeraccepted(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_accepted)
{
//(9)编写处理接受目标函数
//std::thread{std::bind(&Writers::execute_writer, this, std::placeholders::_1), goal_accepted}.detach();
std::thread(std::bind(&Writers::execute_writer, this, goal_accepted)).detach();
}
//(5)创建处理取消目标函数(handle_cancel)
rclcpp_action::CancelResponse handle_writercancel(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_cancel)
{
(void)goal_cancel;
//(10)编写处理取消目标函数
RCLCPP_INFO(this->get_logger(),"收到停止写稿");
if(chapters < 3)
{
stop_writing = true;
RCLCPP_INFO(this->get_logger(),"接受停止写稿");
return rclcpp_action::CancelResponse::ACCEPT;
}
else
{
stop_writing = false;
RCLCPP_INFO(this->get_logger(),"不接受停止写稿");
return rclcpp_action::CancelResponse::REJECT;
}
}
//(6)创建执行目标函数(execute)
void execute_writer(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_execute)
{
//(11)编写执行目标函数
auto feedback = std::make_shared<learning_interfaces2::action::ContractWriter::Feedback>();
auto result = std::make_shared<learning_interfaces2::action::ContractWriter::Result>();
for(int i = 0;i < 5;i++)
{
//判断写作是否被截止
if(stop_writing == true)
{
//文章清零、不在写作
chapters = 0;
writing_in_progress = false;
result->finish = false;
goal_execute->canceled(result);
RCLCPP_INFO(this->get_logger(),"停止写稿");
break;
}
chapters ++;
//发送反馈
//输入反馈内容
feedback->chapter_content.clear();
feedback->chapter_num = chapters;
feedback->chapter_content.push_back("<<没空>>第" + std::to_string(chapters) + "章,我第" + std::to_string(chapters) + "天还是没空");
RCLCPP_INFO(this->get_logger(),"努力写稿中:已写%d章",chapters);
//发送反馈内容
goal_execute->publish_feedback(feedback);
std::this_thread::sleep_for(std::chrono::seconds(5)); //每五秒写一章
//完成目标后告知
if(chapters == 5)
{
//设置结果状态
result->finish = true;
//标记目标成功
goal_execute->succeed(result);
chapters = 0;
writing_in_progress = false;
RCLCPP_INFO(this->get_logger(),"完成全部写稿");
break;
}
}
}
};
int main(int argc,char** argv)
{
rclcpp::init(argc,argv);
auto node = std::make_shared<Writers>("zhao6");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
可以看出,代码比较复杂。
编写动作服务端的步骤:
(1)导入服务接口
(2)声明动作服务端
–分割线–
(3)创建处理目标函数(handle_goal)
(4)创建处理接受目标函数(handle_accepted)
(5)创建处理取消目标函数(handle_cancel)
(6)创建执行目标函数(execute)
(7)创建动作服务端
–分割线–
(8)编写处理目标函数
(9)编写处理接受目标函数
(10)编写处理取消目标函数
(11)编写执行目标函数
步骤看起来有点多,我们可以理一理思绪。
创建动作服务端时,我们需要绑定三个回调函数,我们就从这三个函数下手
- 处理目标函数(handle_goal)
- 处理接受目标函数(handle_accepted)
- 处理取消目标函数(handle_cancel)
根据题目,我们可以梳理出,动作服务端需要做三件事
- 处理客户端的目标请求 (处理目标函数)–> 接受目标后执行目标(处理接受目标函数 --> 执行目标函数)
- 实时发送反馈给客户端 (包含在执行目标函数)
- 完成后发送已完成 (包含在执行目标函数)
还有额外的一件事
- 中途收到客户端取消目标(处理取消目标函数)
那么我们就需要依次编写以上几个回调函数。其中,处理接受目标函数 的作用就是 开启新的线程 调用 执行目标函数,防止阻塞主线程。因为 执行目标、反馈进度、完成任务 都是执行任务时的事情,所以一并放在了执行函数中。
接下来,我们按着步骤编写代码
(1)导入服务接口
#include "learning_interfaces2/action/contract_writer.hpp"
(2)声明动作服务端
模版rclcpp_action::Server<动作服务类型>::SharedPtr 动作服务端对象;
我们声明一个“action_Writer”的动作服务端
rclcpp_action::Server<learning_interfaces2::action::ContractWriter>::SharedPtr action_Writer;
(3)创建处理目标函数(handle_goal)
在handle_writergoal
函数中,
传入参数:BookID
用于表示目标的ID,而参数goal
则用于传递动作服务器接收到的目标消息。
返回参数:GoalResponse
接受或拒绝目标
rclcpp_action::GoalResponse handle_writergoal(const rclcpp_action::GoalUUID& BookID,
std::shared_ptr<const learning_interfaces2::action::ContractWriter::Goal> goal)
{
}
rclcpp_action::GoalUUID BookID
: 这是用于标识目标的唯一标识符。在ROS 2中,每个目标都会有一个唯一的ID,可以用来区分不同的目标。就好比每本书都有自己的ID,这样作者发送给编辑反馈时,就知道哪本是哪本,防止混乱。
std::shared_ptr<const learning_interfaces2::action::ContractWriter::Goal> goal
: 这是指向ContractWriter动作服务器目标消息的智能指针。在ROS 2中,动作服务器会接收目标消息,该消息包含了执行动作所需的参数和信息。这里的goal参数就是指向这个目标消息的指针。
rclcpp_action::GoalResponse
:是 ROS 2 中 rclcpp_action 库提供的一个类型,用于在动作服务器处理动作目标时给动作客户端发送回复。动作服务器接受了目标并将执行它,返回ACCEPT_AND_EXECUTE
。动作服务器拒绝了目标,返回REJECT
。
(4)创建处理接受目标函数(handle_accepted)
处理接受目标函数,它在动作目标被接受后自动被调用。这个函数通常用于启动执行动作目标的进程,例如创建一个线程来执行动作。
void handle_writeraccepted(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_accepted)
{
}
rclcpp_action::ServerGoalHandle
:这是ROS 2动作库中的一个类,代表了一个动作目标的“句柄”,你可以把它想象成一把钥匙,用来控制和访问一个特定的动作目标。
参数goal_accepted
是一个rclcpp_action::ServerGoalHandle
类型的共享指针,它提供了对动作目标的访问。通过这个参数,函数可以访问并操作接收到的目标。
(5)创建处理取消目标函数(handle_cancel)
在handle_writercancel
函数中,通过goal_cancel
参数获取到需要取消的任务的目标句柄,可以根据这个句柄进行相应的取消操作,并返回相应的取消响应。
rclcpp_action::CancelResponse handle_writercancel(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_cancel)
{
}
goal_cancel
: 收到客户端的取消指令后,自动调用此函数,并将需要取消的目标传入goal_cancel
中。
rclcpp_action::CancelResponse
: 是 ROS 2 中 rclcpp_action 库定义的一个枚举类型,用于动作服务器(action server)在处理取消请求时返回给客户端的响应。它表示服务器对取消请求的处理结果。根据服务端的心情,返回给客户端回复。心情好就回复ACCEPT
,心情不好就回复REJECT
。
(6)创建执行目标函数(execute)
void execute_writer(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_execute)
{
}
goal_execute
: 处理接受目标函数(handle_accepted)调用此函数,并将需要执行的目标传入goal_executel
中。
(7)创建动作服务端
创建好需要绑定的几个回调函数后,就可以创建动作服务端了。
模版rclcpp_action::create_server<动作服务类型>( this, "动作服务器的名称", std::bind(&Writers::处理目标函数, this, _1, _2..), std::bind(&Writers::处理取消目标函数, this, _1..), std::bind(&Writers::处理接受目标函数, this, _1..) );
this->action_Writer = rclcpp_action::create_server<learning_interfaces2::action::ContractWriter>(
this,
"contract",
std::bind(&Writers::handle_writergoal, this, _1, _2),
std::bind(&Writers::handle_writercancel, this, _1),
std::bind(&Writers::handle_writeraccepted, this, _1));
(8)编写处理目标函数
编写之前,为了之后编写方便,先声明几个参数,后面会用到
int chapters = 0; //已完成的章节数
bool writing_in_progress = false; //是否正在写作
bool stop_writing = false; //是否停止写作
根据题目,写一个条件语句,若接到的催稿章节为5且赵六不在写作中,则接受目标任务。接受任务后进入写作状态。
RCLCPP_INFO(this->get_logger(),"已收到编辑部的催稿%d章",goal->write_goal);
(void)BookID;
//如果接收到的目标为5,且不在写作中,接受目标,反之都拒绝。
if( (goal->write_goal) == 5 && writing_in_progress == false )
{
RCLCPP_INFO(this->get_logger(),"接受催稿");
writing_in_progress = true; //进入写作状态
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}
else
{
RCLCPP_INFO(this->get_logger(),"拒绝催稿");
return rclcpp_action::GoalResponse::REJECT;
}
(9)编写处理接受目标函数
这行代码的作用是在一个新线程中执行Writers::execute_writer
函数,并传递goal_accepted
参数,从而实现异步执行execute_writer
函数中的操作。
std::thread(std::bind(&Writers::execute_writer, this, goal_accepted)).detach();
std::thread
: 标准线程库中的类,用于创建一个新的线程来执行指定的函数。
.detach()
函数将新创建的线程与主线程分离,使得新线程可以独立执行,不会被主线程阻塞。这样可以实现并发执行,提高程序的效率。
(10)编写处理取消目标函数
赵六通过已编写的章节数来决定是否接受取消请求。如果已编写的章节数少于3章,赵六接受取消请求并停止写稿;否则,取消请求被拒绝,写稿继续进行。
RCLCPP_INFO(this->get_logger(),"收到停止写稿");
(void)goal_cancel;
if(chapters < 3)
{
stop_writing = true;
RCLCPP_INFO(this->get_logger(),"接受停止写稿");
return rclcpp_action::CancelResponse::ACCEPT;
}
else
{
stop_writing = false;
RCLCPP_INFO(this->get_logger(),"不接受停止写稿");
return rclcpp_action::CancelResponse::REJECT;
}
(11)编写执行目标函数
首先,先创建两个指向ContractWriter
动作的反馈和结果的对象。
auto feedback = std::make_shared<learning_interfaces2::action::ContractWriter::Feedback>();
auto result = std::make_shared<learning_interfaces2::action::ContractWriter::Result>();
第一步:判断执行是否被客户端截止(取消)
//判断写作是否被截止
if(stop_writing == true)
{
//文章清零、不在写作
chapters = 0;
writing_in_progress = false;
//设置结果状态
result->finish = false;
//标记目标已取消
goal_execute->canceled(result);
RCLCPP_INFO(this->get_logger(),"停止写稿");
break;
}
第二步:开始写作并实时反馈给客户端
for(int i = 0;i < 5;i++)
{
chapters ++; //每次写一章
//输入反馈内容
feedback->chapter_content.clear(); //清空之前的反馈内容
feedback->chapter_num = chapters; //将章节数放到反馈的chapter_num中
feedback->chapter_content.push_back("<<没空>>第" + std::to_string(chapters) + "章,我第" + std::to_string(chapters) + "天还是没空"); //放入写作的内容
RCLCPP_INFO(this->get_logger(),"努力写稿中:已写%d章",chapters);
//发送反馈内容
goal_execute->publish_feedback(feedback);
std::this_thread::sleep_for(std::chrono::seconds(5)); //每五秒写一章
}
第三步:完成任务告知客户端退出执行
//完成目标后告知
if(chapters == 5)
{
//设置结果状态
result->finish = true;
//标记目标成功
goal_execute->succeed(result);
chapters = 0;
writing_in_progress = false;
RCLCPP_INFO(this->get_logger(),"完成全部写稿");
break;
}
3.编写“催稿”动作客户端孙七
完整代码
/* 编写动作客户端*/
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include <functional>
// (1)导入服务接口
#include "learning_interfaces2/action/contract_writer.hpp"
class Editors : public rclcpp::Node
{
public:
Editors(std::string name) : Node(name)
{
RCLCPP_INFO(this->get_logger(),"编辑节点%s已启动",name.c_str());
//(3)创建动作客户端
action_Editors = rclcpp_action::create_client<learning_interfaces2::action::ContractWriter>
(this,"contract");
}
//(4)创建发送目标函数
void send_writegoal()
{
//等待服务端上线
while(!this->action_Editors->wait_for_action_server(std::chrono::seconds(3)))
{
RCLCPP_INFO(this->get_logger(),"等待作家上线中....");
}
//构建目标
auto goal = std::make_shared<learning_interfaces2::action::ContractWriter::Goal>();
goal->write_goal = 5; //写五章
//创建发送目标时绑定的回调函数
auto send_options = rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SendGoalOptions();
using namespace std::placeholders;
send_options.goal_response_callback =std::bind(&Editors::goal_response_callback, this, _1);
send_options.feedback_callback =std::bind(&Editors::feedback_callback, this, _1, _2);
send_options.result_callback =std::bind(&Editors::result_callback, this, _1);
//发送目标
this->action_Editors->async_send_goal(*goal, send_options);
RCLCPP_INFO(this->get_logger(),"已发送写作目标%d章",goal->write_goal);
}
private:
//(2)声明动作客户端
rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SharedPtr action_Editors;
// (5)创建发送目标反馈函数
void goal_response_callback(const std::shared_ptr
<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>> goal)
{
if(!goal)
{
RCLCPP_INFO(this->get_logger(),"目标已被拒绝");
}
else
{
RCLCPP_INFO(this->get_logger(),"目标已被接受");
}
}
// (6)创建收到反馈函数
void feedback_callback(const std::shared_ptr<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>>& goal_handle,
const std::shared_ptr<const learning_interfaces2::action::ContractWriter::Feedback>& feedback)
{
(void)goal_handle;
RCLCPP_INFO(this->get_logger(),"已收到%d章,小说内容为:%s",feedback->chapter_num,
feedback->chapter_content[0].c_str());
}
// (7)创建收到结果函数
void result_callback(const rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>::WrappedResult & result)
{
switch (result.code)
{
case rclcpp_action::ResultCode::SUCCEEDED:
RCLCPP_INFO(this->get_logger(),"作者已完成写作");
break;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_INFO(this->get_logger(),"作者已取消写作");
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(),"因错误而终止");
rclcpp::shutdown();
break;
default:
RCLCPP_ERROR(this->get_logger(),"未知错误");
rclcpp::shutdown();
break;
}
}
};
int main(int argc,char** argv)
{
rclcpp::init(argc,argv);
auto node = std::make_shared<Editors>("sun7");
node->send_writegoal();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
编写动作客户端的步骤
(1)导入服务接口
(2)声明动作客户端
(3)创建动作客户端
(4)创建和编写发送目标函数
(5)创建和编写发送目标反馈函数
(6)创建和编写收到反馈函数
(7)创建和编写收到结果函数
动作客户端通常会对应服务端的响应,来创建回调函数。
首先,客户端会发送给服务端一个目标。(发送目标函数)
然后,服务端根据自己的情况来回复客户端是否接受目标。(发送目标反馈函数)
若服务端接受目标,那么服务端就会在执行过程中,给客户端反馈进度(收到反馈函数)和写作结果(收到结果函数)。
(1)导入服务接口
#include "learning_interfaces2/action/contract_writer.hpp"
(2)声明动作客户端
模版:rclcpp_action::Client<服务类型>::SharedPtr 动作客户端对象
//(2)声明动作客户端
rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SharedPtr action_Editors;
(3)创建动作客户端
模版:动作客户端对象 = rclcpp_action::create_client<服务类型>(this,"动作名称");
//(3)创建动作客户端
action_Editors = rclcpp_action::create_client<learning_interfaces2::action::ContractWriter>(this,"contract");
(4)创建和编写发送目标函数
第一步: 创建发送目标函数。
//(4)创建发送目标函数
void send_writegoal()
{
}
第二步: 等待服务端上线
等待动作服务端启动,如果在3秒内没有启动,就输出"等待作家上线中…"的信息,并继续等待,直到服务器启动或程序退出。
//等待服务端上线
while(!this->action_Editors->wait_for_action_server(std::chrono::seconds(3)))
{
RCLCPP_INFO(this->get_logger(),"等待作家上线中....");
}
wait_for_action_server
函数是rclcpp库中的一个功能,它会尝试与服务端建立连接,并在服务端就绪时返回true,如果超时则返回false。
while(!this->action_Editors->wait_for_action_server(std::chrono::seconds(3)))
这个循环是,每隔三秒检查服务端是否上线,如果没有就返回false,然后继续等待,直到返回true或者程序退出。
第三步: 构建目标
//构建目标
auto goal = std::make_shared<learning_interfaces2::action::ContractWriter::Goal>();
goal->write_goal = 5; //写五章
learning_interfaces2::action::ContractWriter
表示的是服务类型。
服务类型::Goal
表示的是服务类型里面的目标,它定义了执行动作服务所需的参数。
goal->write_goal
表示访问 Goal 对象中的 write_goal
成员变量,并将其设置为 5。
第四步: 创建发送目标时绑定的回调函数
这段代码的目的是为动作客户端发送目标时设置回调函数,以便在动作的生命周期中(如响应、反馈和结果)得到通知并进行相应的处理。
//创建发送目标时绑定的回调函数
auto send_options = rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SendGoalOptions();
using namespace std::placeholders;
send_options.goal_response_callback =std::bind(&Editors::goal_response_callback, this, _1);
send_options.feedback_callback =std::bind(&Editors::feedback_callback, this, _1, _2);
send_options.result_callback =std::bind(&Editors::result_callback, this, _1);
首先,创建了一个SendGoalOptions
对象send_options
,SendGoalOptions
它是rclcpp_action::Client模板类的一个成员函数,用于设置发送目标时的选项。
在使用 rclcpp_action::Client
发送动作目标(goal)时,通常会绑定三个回调函数:
-
goal_response_callback
:这个回调函数会在动作服务器接受或拒绝客户端发送的动作目标时被调用。它通常用于处理服务器对目标的响应,比如确认收到目标或拒绝目标等。 -
feedback_callback
:这个回调函数会在动作执行过程中,每当动作服务器发送反馈消息时被调用。它通常用于接收动作执行过程中的状态更新或进度信息。 -
result_callback
:这个回调函数会在动作完成后被调用,无论是成功完成还是失败。它用于接收动作执行的结果,并根据结果执行相应的逻辑。
当你发送一个动作目标时,首先会被调用的是 goal_response_callback
,因为动作服务器会立即响应是否接受该目标。
如果动作服务器接受了目标并开始执行,那么在执行过程中,feedback_callback
会被多次调用,以提供关于动作执行进度的信息。
当动作完成后,result_callback
会被调用一次,以提供动作执行的结果。
第五步: 发送目标
这行代码调用async_send_goal
成员函数,异步发送一个目标给动作服务端。
//发送目标
this->action_Editors->async_send_goal(*goal, send_options);
RCLCPP_INFO(this->get_logger(),"已发送写作目标%d章",goal->write_goal);
async_send_goal
是动作客户端的一个成员函数,用于异步地发送一个动作目标给服务器。这个函数有两个参数:
- 第一个参数
*goal
是一个指向你要发送的动作目标的指针。 - 第二个参数
send_options
是一个SendGoalOptions
类型的对象,它包含了发送目标时的配置选项,包括之前你绑定的三个回调函数。
当调用 async_send_goal
函数后,动作客户端会尝试将目标发送给服务器,并且不会阻塞等待服务器的响应。相反,它会立即返回,并且当服务器响应、发送反馈或返回结果时,之前绑定的回调函数会被调用。
(5)创建和编写发送目标反馈函数
当动作服务端接受或拒绝一个动作目标时,它会通过调用在SendGoalOptions
(服务端)中设置的回调函数来通知客户端。
对于接受的情况,服务端会发送一个接受消息给客户端,然后客户端的ClientGoalHandle
(客户端)会被标记为“已接受”,反之同理。
// (5)创建发送目标反馈函数
void goal_response_callback(const std::shared_ptr
<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>> goal)
{
if(!goal)
{
RCLCPP_INFO(this->get_logger(),"目标已被拒绝");
}
else
{
RCLCPP_INFO(this->get_logger(),"目标已被接受");
}
}
ClientGoalHandle
:这可以被看作是一个“任务管理器”。当你给动作服务器发送一个任务时,帮助你跟踪这个任务的状态。它告诉你任务是否已经被接受、正在执行、或者已经完成。
if(!goal)
:这行代码检查传入的goal
指针是否为空。如果为空,表示动作服务器拒绝了目标。
(6)创建和编写收到反馈函数
该函数用于处理从动作服务器接收到的反馈的回调函数。
// (6)创建收到反馈函数
void feedback_callback(
const std::shared_ptr<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>>& goal_handle,
const std::shared_ptr<const learning_interfaces2::action::ContractWriter::Feedback>& feedback)
{
RCLCPP_INFO(this->get_logger(),"已收到%d章,小说内容为:%s",feedback->chapter_num,feedback->chapter_content[0].c_str());
}
这个函数有两个参数:
goal_handle
:这是一个指向 ClientGoalHandle
的共享指针,它代表了你发送给服务端的动作目标。通过这个 goal_handle
,你可以取消目标、获取目标状态等。(本次未使用)
feedback
:这是一个指向ContractWriter::Feedback
消息类型的常量共享指针。这个消息包含了动作服务器发送的反馈数据。在此,这个反馈数据包括 chapter_num
(章节号)和 chapter_content
(章节内容)。
(7)创建和编写收到结果函数
这个回调函数用于处理动作客户端从动作服务器接收到的结果。这个回调函数会在动作任务完成时被调用,并根据任务的结果执行不同的逻辑。
// (7)创建收到结果函数
void result_callback(const rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>::WrappedResult & result)
{
switch (result.code)
{
case rclcpp_action::ResultCode::SUCCEEDED:
RCLCPP_INFO(this->get_logger(),"作者已完成写作");
break;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_INFO(this->get_logger(),"作者已取消写作");
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(),"因错误而终止");
rclcpp::shutdown();
break;
default:
RCLCPP_ERROR(this->get_logger(),"未知错误");
rclcpp::shutdown();
break;
}
}
该函数接收一个WrappedResult
对象result
,它封装了动作的结果,包括结果代码和结果消息。
使用switch
语句根据result.code
的值来决定执行哪个分支的代码。如果结果代码是SUCCEEDED
,表示任务成功完成。其他同理。
五、完整代码
zhao6.cpp
/* 编写动作服务端*/
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
// (1)导入服务接口
#include "learning_interfaces2/action/contract_writer.hpp"
class Writers : public rclcpp::Node
{
public:
Writers(std::string name) : Node(name)
{
RCLCPP_INFO(this->get_logger(),"作家节点%s已启动",name.c_str());
using namespace std::placeholders;
//(7)创建动作服务端
this->action_Writer = rclcpp_action::create_server<learning_interfaces2::action::ContractWriter>(
this,
"contract",
std::bind(&Writers::handle_writergoal, this, _1, _2),
std::bind(&Writers::handle_writercancel, this, _1),
std::bind(&Writers::handle_writeraccepted, this, _1));
}
private:
//(2)声明动作服务端
rclcpp_action::Server<learning_interfaces2::action::ContractWriter>::SharedPtr action_Writer;
int chapters = 0; //已完成的章节数
bool writing_in_progress = false; //是否正在写作
bool stop_writing = false; //是否停止写作
//(3)创建处理目标函数(handle_goal)
rclcpp_action::GoalResponse handle_writergoal(const rclcpp_action::GoalUUID& BookID,
std::shared_ptr<const learning_interfaces2::action::ContractWriter::Goal> goal)
{
//(8)编写处理目标函数
RCLCPP_INFO(this->get_logger(),"已收到编辑部的催稿%d章",goal->write_goal);
(void)BookID;
//如果接收到的目标为5,且不在写作中,接受目标,反之都拒绝。
if( (goal->write_goal) == 5 && writing_in_progress == false )
{
RCLCPP_INFO(this->get_logger(),"接受催稿");
writing_in_progress = true; //进入写作状态
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}
else
{
RCLCPP_INFO(this->get_logger(),"拒绝催稿");
return rclcpp_action::GoalResponse::REJECT;
}
}
//(4)创建处理接受目标函数(handle_accepted)
void handle_writeraccepted(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_accepted)
{
//(9)编写处理接受目标函数
//std::thread{std::bind(&Writers::execute_writer, this, std::placeholders::_1), goal_accepted}.detach();
std::thread(std::bind(&Writers::execute_writer, this, goal_accepted)).detach();
}
//(5)创建处理取消目标函数(handle_cancel)
rclcpp_action::CancelResponse handle_writercancel(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_cancel)
{
(void)goal_cancel;
//(10)编写处理取消目标函数
RCLCPP_INFO(this->get_logger(),"收到停止写稿");
if(chapters < 3)
{
stop_writing = true;
RCLCPP_INFO(this->get_logger(),"接受停止写稿");
return rclcpp_action::CancelResponse::ACCEPT;
}
else
{
stop_writing = false;
RCLCPP_INFO(this->get_logger(),"不接受停止写稿");
return rclcpp_action::CancelResponse::REJECT;
}
}
//(6)创建执行目标函数(execute)
void execute_writer(const std::shared_ptr<rclcpp_action::ServerGoalHandle<learning_interfaces2::action::ContractWriter>> goal_execute)
{
//(11)编写执行目标函数
auto feedback = std::make_shared<learning_interfaces2::action::ContractWriter::Feedback>();
auto result = std::make_shared<learning_interfaces2::action::ContractWriter::Result>();
for(int i = 0;i < 5;i++)
{
//判断写作是否被截止
if(stop_writing == true)
{
//文章清零、不在写作
chapters = 0;
writing_in_progress = false;
result->finish = false;
goal_execute->canceled(result);
RCLCPP_INFO(this->get_logger(),"停止写稿");
break;
}
chapters ++;
//发送反馈
//输入反馈内容
feedback->chapter_content.clear();
feedback->chapter_num = chapters;
feedback->chapter_content.push_back("<<没空>>第" + std::to_string(chapters) + "章,我第" + std::to_string(chapters) + "天还是没空");
RCLCPP_INFO(this->get_logger(),"努力写稿中:已写%d章",chapters);
//发送反馈内容
goal_execute->publish_feedback(feedback);
std::this_thread::sleep_for(std::chrono::seconds(5)); //每五秒写一章
//完成目标后告知
if(chapters == 5)
{
//设置结果状态
result->finish = true;
//标记目标成功
goal_execute->succeed(result);
chapters = 0;
writing_in_progress = false;
RCLCPP_INFO(this->get_logger(),"完成全部写稿");
break;
}
}
}
};
int main(int argc,char** argv)
{
rclcpp::init(argc,argv);
auto node = std::make_shared<Writers>("zhao6");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
sun7.cpp
/* 编写动作客户端*/
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include <functional>
// (1)导入服务接口
#include "learning_interfaces2/action/contract_writer.hpp"
class Editors : public rclcpp::Node
{
public:
Editors(std::string name) : Node(name)
{
RCLCPP_INFO(this->get_logger(),"编辑节点%s已启动",name.c_str());
//(3)创建动作客户端
action_Editors = rclcpp_action::create_client<learning_interfaces2::action::ContractWriter>
(this,"contract");
}
//(4)创建发送目标函数
void send_writegoal()
{
//等待服务端上线
while(!this->action_Editors->wait_for_action_server(std::chrono::seconds(3)))
{
RCLCPP_INFO(this->get_logger(),"等待作家上线中....");
}
//构建目标
auto goal = std::make_shared<learning_interfaces2::action::ContractWriter::Goal>();
goal->write_goal = 5; //写五章
//创建发送目标时绑定的回调函数
auto send_options = rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SendGoalOptions();
using namespace std::placeholders;
send_options.goal_response_callback =std::bind(&Editors::goal_response_callback, this, _1);
send_options.feedback_callback =std::bind(&Editors::feedback_callback, this, _1, _2);
send_options.result_callback =std::bind(&Editors::result_callback, this, _1);
//发送目标
this->action_Editors->async_send_goal(*goal, send_options);
RCLCPP_INFO(this->get_logger(),"已发送写作目标%d章",goal->write_goal);
}
private:
//(2)声明动作客户端
rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SharedPtr action_Editors;
// (5)创建发送目标反馈函数
void goal_response_callback(const std::shared_ptr
<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>> goal)
{
if(!goal)
{
RCLCPP_INFO(this->get_logger(),"目标已被拒绝");
}
else
{
RCLCPP_INFO(this->get_logger(),"目标已被接受");
}
}
// (6)创建收到反馈函数
void feedback_callback(const std::shared_ptr<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>>& goal_handle,
const std::shared_ptr<const learning_interfaces2::action::ContractWriter::Feedback>& feedback)
{
(void)goal_handle;
RCLCPP_INFO(this->get_logger(),"已收到%d章,小说内容为:%s",feedback->chapter_num,
feedback->chapter_content[0].c_str());
}
// (7)创建收到结果函数
void result_callback(const rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>::WrappedResult & result)
{
switch (result.code)
{
case rclcpp_action::ResultCode::SUCCEEDED:
RCLCPP_INFO(this->get_logger(),"作者已完成写作");
break;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_INFO(this->get_logger(),"作者已取消写作");
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(),"因错误而终止");
rclcpp::shutdown();
break;
default:
RCLCPP_ERROR(this->get_logger(),"未知错误");
rclcpp::shutdown();
break;
}
}
};
int main(int argc,char** argv)
{
rclcpp::init(argc,argv);
auto node = std::make_shared<Editors>("sun7");
node->send_writegoal();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
另一个版本的sun7.cpp
,加上了定时器
/* 编写动作客户端*/
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include <functional>
// (1)导入服务接口
#include "learning_interfaces2/action/contract_writer.hpp"
class Editors : public rclcpp::Node
{
public:
Editors(std::string name) : Node(name)
{
RCLCPP_INFO(this->get_logger(),"编辑节点%s已启动",name.c_str());
//(3)创建动作客户端
action_Editors = rclcpp_action::create_client<learning_interfaces2::action::ContractWriter>(this,"contract");
// 补充 创建定时器
WritersTimer = this->create_wall_timer(std::chrono::seconds(20),std::bind(&Editors::send_writegoal, this));
}
//(4)创建发送目标函数
void send_writegoal()
{
//等待服务端上线
while(!this->action_Editors->wait_for_action_server(std::chrono::seconds(3)))
{
RCLCPP_INFO(this->get_logger(),"等待作家上线中....");
}
//构建目标
auto goal = std::make_shared<learning_interfaces2::action::ContractWriter::Goal>();
goal->write_goal = 5; //写五章
//创建发送目标时绑定的回调函数
auto send_options = rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SendGoalOptions();
using namespace std::placeholders;
send_options.goal_response_callback =std::bind(&Editors::goal_response_callback, this, _1);
send_options.feedback_callback =std::bind(&Editors::feedback_callback, this, _1, _2);
send_options.result_callback =std::bind(&Editors::result_callback, this, _1);
//发送目标
this->action_Editors->async_send_goal(*goal, send_options);
RCLCPP_INFO(this->get_logger(),"已发送写作目标%d章",goal->write_goal);
}
private:
//(2)声明动作客户端
rclcpp_action::Client<learning_interfaces2::action::ContractWriter>::SharedPtr action_Editors;
// 补充定时器
rclcpp::TimerBase::SharedPtr WritersTimer;
// (5)创建发送目标反馈函数
void goal_response_callback
(const std::shared_ptr<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>> goal)
{
if(!goal)
{
RCLCPP_INFO(this->get_logger(),"目标已被拒绝");
}
else
{
RCLCPP_INFO(this->get_logger(),"目标已被接受");
}
}
// (6)创建收到反馈函数
void feedback_callback(const std::shared_ptr
<rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>>& goal_handle,
const std::shared_ptr<const learning_interfaces2::action::ContractWriter::Feedback>& feedback)
{
(void)goal_handle;
RCLCPP_INFO(this->get_logger(),"已收到%d章,小说内容为:%s",feedback->chapter_num,feedback->chapter_content[0].c_str());
}
// (7)创建收到结果函数
void result_callback(const rclcpp_action::ClientGoalHandle<learning_interfaces2::action::ContractWriter>::WrappedResult & result)
{
switch (result.code)
{
case rclcpp_action::ResultCode::SUCCEEDED:
RCLCPP_INFO(this->get_logger(),"作者已完成写作");
break;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_INFO(this->get_logger(),"作者已取消写作");
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(),"因错误而终止");
rclcpp::shutdown();
break;
default:
RCLCPP_ERROR(this->get_logger(),"未知错误");
rclcpp::shutdown();
break;
}
}
};
int main(int argc,char** argv)
{
rclcpp::init(argc,argv);
auto node = std::make_shared<Editors>("sun7");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
六、编译
打开一个终端
cd towm_ws
colcon build --packages-select learning_action
source install/setup.sh
ros2 run learning_action sun7_node
打开另一个终端
source install/setup.sh
ros2 run learning_action zhao6_node
(1)未加入定时器
(2)加入定时器
总结
自用