Action通信 Server端实现
创建服务端功能包(注意目录层级):
ros2 pkg create my_exer05_action_server --build-type ament_cmake --node-name nav_server --dependencies rclcpp rclcpp_action my_exer_interfaces nav_msgs
/*
需求:简单的模拟导航功能,向机器人发送一个前进N米的请求,机器人就会以 0.1m/s的速度前进,
当与目标点的距离小于0.05m时,机器人就会停止运动,返回机器人的停止坐标,并且在此过程中,
会连续反馈机器人与目标点之间的剩余距离。
流程:
1.包含头文件;
2.初始化ROS2客户端;
3.自定义节点类;
3-1.创建参数服务客户端,连接到速度发布节点;
3-2.创建订阅方,订阅机器人的里程计以获取机器人坐标;
3-3.创建动作服务端,解析客户端的相关并生成响应。
4.调用spin函数,并传入节点对象指针;
5.资源释放。
*/
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "exer_interfaces/action/nav.hpp"
using namespace std::chrono_literals;
using namespace std::placeholders;
// 3.自定义节点类;
class NavServer: public rclcpp::Node{
public:
NavServer():Node("nav_server_node_cpp"){
last_x = 0.0;
last_y = 0.0;
// 3-1.创建参数服务客户端,连接到速度发布节点;
paramClient = std::make_shared<rclcpp::AsyncParametersClient>(this,"pub_vel_node_cpp");
// 等待服务连接
while (!paramClient->wait_for_service(1s))
{
if (!rclcpp::ok())
{
return;
}
RCLCPP_INFO(this->get_logger(),"服务未连接");
}
//
RCLCPP_INFO(this->get_logger(),"已经连接成功速度发送节点的参数服务,可以设置线速度和角速度了");
// 3-2.创建订阅方,订阅机器人的里程计以获取机器人坐标;
sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>("odom",10,std::bind(&NavServer::on_timer,this,_1));
// 3-3.创建动作服务端,解析客户端的相关并生成响应。
nav_action_server_ = rclcpp_action::create_server<exer_interfaces::action::Nav>(
this,
"nav",
std::bind(&NavServer::handle_goal,this,_1,_2),
std::bind(&NavServer::handle_cancel,this,_1),
std::bind(&NavServer::handle_accepted,this,_1)
);
}
private:
rclcpp::AsyncParametersClient::SharedPtr paramClient;
double x,y; // 当前机器人坐标
double last_x,last_y; // 每次导航时,机器人起点坐标
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
rclcpp_action::Server<exer_interfaces::action::Nav>::SharedPtr nav_action_server_;
void on_timer(const nav_msgs::msg::Odometry & odom){
x = odom.pose.pose.position.x;
y = odom.pose.pose.position.y;
}
// 解析动作客户端发送的请求;
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID & goal_uuid, std::shared_ptr<const exer_interfaces::action::Nav::Goal> goal){
(void)goal_uuid;
float x = goal->goal;
if (x > 0.0)
{
RCLCPP_INFO(this->get_logger(),"请求前进%.2f米", x);
} else {
RCLCPP_INFO(this->get_logger(),"只许进,不许退!");
return rclcpp_action::GoalResponse::REJECT;
}
paramClient->set_parameters({rclcpp::Parameter("linear",0.1),rclcpp::Parameter("angular",0.0)});
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}
// 处理动作客户端发送的取消请求;
rclcpp_action::CancelResponse handle_cancel(std::shared_ptr<rclcpp_action::ServerGoalHandle<exer_interfaces::action::Nav>> goal_handle){
(void)goal_handle;
RCLCPP_INFO(this->get_logger(),"任务取消中....!");
paramClient->set_parameters({rclcpp::Parameter("linear",0.0),rclcpp::Parameter("angular",0.0)});
return rclcpp_action::CancelResponse::ACCEPT;
}
void execute(std::shared_ptr<rclcpp_action::ServerGoalHandle<exer_interfaces::action::Nav>> goal_handle){
RCLCPP_INFO(this->get_logger(),"开始执行任务......");
// 获取目标点
float goal = goal_handle->get_goal()->goal;
// 连续反馈
auto feedback = std::make_shared<exer_interfaces::action::Nav::Feedback>();
// 最终结果
auto result = std::make_shared<exer_interfaces::action::Nav::Result>();
// 设置连续反馈
rclcpp::Rate rate(1.0);
while(rclcpp::ok()){
// 检查任务是否被取消;
if(goal_handle->is_canceling()){
result->x = x;
result->y = y;
goal_handle->canceled(result);
RCLCPP_INFO(this->get_logger(), "任务取消");
last_x = x;
last_y = y;
paramClient->set_parameters({rclcpp::Parameter("linear",0.0),rclcpp::Parameter("angular",0.0)});
return;
}
double distance = goal - (x - last_x);
feedback->distance = distance;
goal_handle->publish_feedback(feedback);
if (distance <= 0.1)
{
break;
}
rate.sleep();
}
// 设置最终结果
if (rclcpp::ok()) {
result->x = x;
result->y = y;
last_x = x;
last_y = y;
goal_handle->succeed(result);
paramClient->set_parameters({rclcpp::Parameter("linear",0.0),rclcpp::Parameter("angular",0.0)});
RCLCPP_INFO(this->get_logger(), "任务完成!");
}
}
// 创建新线程处理请求;
void handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<exer_interfaces::action::Nav>> goal_handle){
std::thread{std::bind(&NavServer::execute,this,_1),goal_handle}.detach();
}
};
int main(int argc, char const *argv[])
{
// 2.初始化ROS2客户端;
rclcpp::init(argc,argv);
// 4.调用spain函数,并传入节点对象指针;
rclcpp::spin(std::make_shared<NavServer>());
// 5.资源释放。
rclcpp::shutdown();
return 0;
}
案例4:
-------------运行动作服务端 测试-----------
进入ws03_exercise目录下
ros2 launch stage_ros2 my_house.launch.py // 启动 stage仿真环境
ros2 run my_exer01_topic_pub pub_vel // 启动速度发布方
ros2 run my_exer05_action_server nav_server // 启动Action服务端
ros2 action send_goal /nav my_exer_interfaces/action/Nav "{'goal': 10.0}" -f // 命令行方式,传递目标点 前进10m
Action通信 Client端实现
创建客户端功能包(注意目录层级):
ros2 pkg create my_exer06_action_client --build-type ament_cmake --node-name nav_client --dependencies rclcpp rclcpp_action my_exer_interfaces
/*
需求:向服务端提交数据(浮点类型前进距离),并处理响应
流程:
1. 包含头文件;
2. 初始化 ROS2 客户端;
3. 处理终端提交的数据;
4. 自定义节点类;
4-1.创建动作通信客户端
4-2.编写发送请求函数
4-3.处理服务端返回的“请求数据是否合法”
4-4.处理服务端的连续反馈
4-5.处理最终响应
4-6.特定条件下发送取消请求。
a.条件:客户端按下ctrl + c rclcpp::ok()
b.发送取消任务请求 action_client_->async_cancel_goal(goal_handle)
5. 调用自定义节点类对象向服务端发送数据;
6. 调用 spin 函数,并传入节点对象指针;
7. 释放资源;
*/
// 包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "my_exer_interfaces/action/nav.hpp"
using namespace std::placeholders;
using namespace std::chrono_literals;
using my_exer_interfaces::action::Nav;
// 自定义节点类;
class NavClient : public rclcpp::Node{
public:
NavClient(): Node("nav_client_node_cpp"){
RCLCPP_INFO(this->get_logger(), "NavClient创建!}");
// 4-1.创建动作通信客户端
action_client_ = rclcpp_action::create_client<Nav>(this,"/nav");
}
// 4-2.编写发送请求函数
void send_goal(double goal){
// 1.保证可以连接到服务端
if(!action_client_->wait_for_action_server(10s))
{
RCLCPP_ERROR(this->get_logger(),"连接超时!");
return;
}
RCLCPP_INFO(this->get_logger(),"连接成功!");
// 2.组织被发送的请求对象
auto request = Nav::Goal();
request.goal = goal;
// 3.封装回调函数
rclcpp_action::Client<Nav>::SendGoalOptions options;
// std::function<void (typename GoalHandle::SharedPtr)>;
options.goal_response_callback = std::bind(&NavClient::goal_response_callback,this,_1);
// std::function<void (typename ClientGoalHandle<ActionT>::SharedPtr,const std::shared_ptr<const Feedback>)>;
options.feedback_callback = std::bind(&NavClient::feedback_callback,this,_1,_2);
// std::function<void (const WrappedResult & result)>;
options.result_callback = std::bind(&NavClient::result_callback,this,_1);
// 4.发送
action_client_->async_send_goal(request, options); // 核心API
}
private:
rclcpp_action::Client<Nav>::SharedPtr action_client_;
// 4-3.处理服务端返回的“请求数据是否合法”
void goal_response_callback(rclcpp_action::ClientGoalHandle<Nav>::SharedPtr goal_handle){
if(!goal_handle){
RCLCPP_ERROR(this->get_logger(),"请求数据非法,请先检查提交的是否是一个正数。");
}else{
RCLCPP_INFO(this->get_logger(),"请求数据被受理!");
// 单独一根线程,循环判断终端状态
std::thread{std::bind(&NavClient::cancel, this,_1), goal_handle}.detach();
}
}
void cancel(rclcpp_action::ClientGoalHandle<Nav>::SharedPtr goal_handle){
// 当rclcpp::ok() 返回 false 时,表示终端被按下了 ctrl + c , 取消任务
while(rclcpp::ok()){}
action_client_->async_cancel_goal(goal_handle);
}
// 4-4.处理服务端的连续反馈
void feedback_callback(rclcpp_action::ClientGoalHandle<Nav>::SharedPtr goal_handle,const std::shared_ptr<const Nav::Feedback> feedback){
// 直接将机器人和目标点之间的剩余距离输出
(void)goal_handle;
RCLCPP_INFO(this->get_logger(),"剩余距离:%.2f",feedback->distance);
}
// 4-5.处理最终响应
void result_callback(const rclcpp_action::ClientGoalHandle<Nav>::WrappedResult & result){
// 输出机器人的停止坐标
if (result.code == rclcpp_action::ResultCode::SUCCEEDED)
{
RCLCPP_INFO(this->get_logger(),"导航成功!");
RCLCPP_INFO(this->get_logger(),"机器人停止的坐标:(%.2f,%.2f)",result.result->x,result.result->y);
}else{
RCLCPP_ERROR(this->get_logger(),"机器人没有到达目标点!");
}
rclcpp::shutdown();
}
};
int main(int argc, char * argv[]){
// 2.初始化 ROS2 客户端;
rclcpp::init(argc, argv);
// 3.处理终端提交的数据;
if(argc != 2){
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),"请提交一个距离数据!");
return 1;
}
auto nav_client = std::make_shared<NavClient>();
// 5.调用自定义节点类对象向服务端发送数据
nav_client->send_goal(atof(argv[1]));
// 6.调用 spin 函数,并传入节点对象指针。
rclcpp::spin(nav_client);
// 7.释放资源;
rclcpp::shutdown();
return 0;
}
两种测试方案
1. 用stage仿真环境测试
2.用实体机器人测试