ROS2中,小车通信服务通信

服务端:

/*
    需求:巡航服务端,当客户端发送请求时,如果请求数据是1那么开始巡航,如果是0那么就结束巡航,
         并且无论是开始巡航还是结束巡航,都需要返回机器人当时的坐标。
        功能点1:提取请求数据并处理   提取请求数据并获取
            0   终止巡航   终止
            非0  开始(设置速度而已   开始
            核心:怎么向机器人发送速度指令(参考需求1  vel_pub
        功能点1实现:
            复用topic01实现
            如何复用?
            1topic以动态参数的方式提供了对外接口;
            2.创建参数客户端向topic01注入参数即可
            优点:
            1.增强代码的复用性;  //复用需求1的实现  做一个参数客户端 
            2.增强可维护性 //可维护性能高 增强了可维护性

        功能点2:动态生成响应结果
            通过里程计获取机器人坐标   ,通过里程计获取机器人坐标
    流程:
        1.包含头文件;
        2.初始化ROS2客户端;
        3.自定义节点类;
          3-1.创建参数服务客户端,连接到速度发布节点;
          3-2.创建订阅方,订阅机器人的里程计以获取机器人坐标。
          3-3.创建服务端,处理客户端请求,如果提交的是1,那么通过参数客户端设置有效的角速度、线速度数据,
              如果是0,那么通过参数客户端将速度指令置0。
        4.调用spin函数,并传入节点对象指针;
        5.资源释放。
*/
// 1.包含头文件;
// 包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "myexer_interfaces/srv/cru.hpp"
#include "nav_msgs/msg/odometry.hpp"


using namespace std::chrono_literals;
using namespace std::placeholders;

// 自定义节点类;   
class CruServer : public rclcpp::Node{
public:
    CruServer(): Node("cru_server_node_cpp"){
        RCLCPP_INFO(this->get_logger(), "CruServer创建!}");

        // 3-1创建参数服务客户端,连接速度发布节点
        paramClient = std::make_shared<rclcpp::AsyncParametersClient>(this,"pub_vel_node_cpp");

        // //等待连接
        // while(!paramClient->wait_for_service(1s))
        // {
        //     if(!rclcpp::ok())
        //     {
        //         RCLCPP_INFO(this->get_logger(),"服务取消,现在退出");
        //         return;
        //     }

        //     RCLCPP_INFO(this->get_logger(),"服务还没有连接");

        // }
        while(!paramClient->wait_for_service(1s))
        {
            if(!rclcpp::ok())
            {
                RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"服务取消,现在退出!");
                return;
            }

            RCLCPP_INFO(this->get_logger(),"服务还没有连接");
        }
        
        this->declare_parameter<double>("linear",0.0);
        this->declare_parameter<double>("amgular",0.0);

        //3.2 创建订阅方,订阅机器人的里程计信息
        sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>("odom",10,std::bind(&CruServer::on_timer,this,_1));   //里程计消息,队列10,回调


        // 3-3.创建服务端,处理客户端请求,如果提交的是1,那么通过参数客户端设置有效的角速度、线速度数据,
        //     如果是0,那么通过参数客户端将速度指令置0。
        service = this->create_service<myexer_interfaces::srv::Cru>("cruising",std::bind(&CruServer::cb,this,_1,_2));

        
    }

private:

    // rclcpp::AsyncParametersClient::SharedPtr paramClient;
    rclcpp::AsyncParametersClient::SharedPtr paramClient;
    // rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
    rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
    rclcpp::Service<myexer_interfaces::srv::Cru>::SharedPtr service;
    double x,y;

    void on_timer(const nav_msgs::msg::Odometry &odom)   //这里主要注意传参
    {
        //解析订阅到的x , y 坐标
        // x = odom.pose.pose.position.x;
        // y = odom.pose.pose.position.y;
        x = odom.pose.pose.position.x;
        y = odom.pose.pose.position.y;
    }


    void cb(const myexer_interfaces::srv::Cru::Request::SharedPtr req,myexer_interfaces::srv::Cru::Response::SharedPtr res)
    {
        int flag = req->flag;
        RCLCPP_INFO(this->get_logger(),"客户端提交的数据为:%d",flag);
        double linear = 0.0,angular = 0.0;
        //判断提交的数据
        if(flag != 0)  //开始巡航     
        {
            RCLCPP_INFO(this->get_logger(),"开始巡航......");
            linear  = 1.0;   //线速度
            angular = 0.0;   //角速度

        }else{   //终止巡航
            RCLCPP_INFO(this->get_logger(),"巡航......结束......");
            linear  = 0.0;   //线速度
            angular = 0.0;   //角速度
        }

        paramClient->set_parameters({rclcpp::Parameter("linear",linear),rclcpp::Parameter("angular",angular)});



        res->x = x;
        res->y = y;
    }
    

};

int main(int argc, char * argv[]){
    // 初始化 ROS2 客户端;
    rclcpp::init(argc, argv);
    // 调用 spin 函数,并传入节点对象指针。
    rclcpp::spin(std::make_shared<CruServer>());
    // 释放资源;
    rclcpp::shutdown();
    return 0;
}


客户端:

/*
    需求:向巡航服务端发送请求数据,如果发送的是非0数据,那么就开始巡航,否则就终止巡航,
         不论何种请求,服务端响应的数据是机器人的坐标,客户端还需要解析结果并输出在终端。
    GONG
    流程:
        1.包含头文件;
        2.初始化ROS2客户端;
        3.自定义节点类;
          3-1.创建客户端;
          3-2.连接服务端;
          3-3.发送请求。
        4.创建自定义类对象,并调用连接服务以及请求发送请求的函数;
        5.处理响应结果;
        6.资源释放。
*/
// 1.包含头文件;
// 包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "myexer_interfaces/srv/cru.hpp"

using namespace std::chrono_literals;

// 自定义节点类;
class CruClient : public rclcpp::Node{
public:
    CruClient(): Node("cru_client_node_cpp"){
        RCLCPP_INFO(this->get_logger(), "CruClient创建!}");
        client = this->create_client<myexer_interfaces::srv::Cru>("cruising");
        RCLCPP_INFO(this->get_logger(),"客户端创建,等待连接!");
        
    }
     //等待连接
        bool connect_server()
        {
            while(!client->wait_for_service(1s))
            {
                if(!rclcpp::ok())
                {
                    return false;
                }
                 RCLCPP_INFO(this->get_logger(),"服务连接中,请稍后.....");
            }

           return true;
        }


        //发送请求的函数
        rclcpp::Client<myexer_interfaces::srv::Cru>::FutureAndRequestId send_request(int32_t flag){

            //将flag封装成cru的请求对象
            auto request = std::make_shared<myexer_interfaces::srv::Cru::Request>();
            request->flag = flag;

            //发送到服务器(服务器给响应)
            return client->async_send_request(request);
        }


private:
    rclcpp::Client<myexer_interfaces::srv::Cru>::SharedPtr client;
};

int main(int argc, char * argv[]){
    // 初始化 ROS2 客户端;
    rclcpp::init(argc, argv);
    
    //创建自定义对象
    auto client = std::make_shared<CruClient>();

    bool flag = client ->connect_server();
    if(!flag)
    {
        RCLCPP_INFO(rclcpp::get_logger("dds"),"服务连接失败");
    }

    //发送请求
    auto response = client -> send_request(atoi(argv[1]));

    if(rclcpp::spin_until_future_complete(client,response) == rclcpp::FutureReturnCode::SUCCESS)
    {
        RCLCPP_INFO(client->get_logger(),"请求正常处理");
        auto cru_res = response.get();
        RCLCPP_INFO(client->get_logger(),"响应坐标:(%.3f,%.3f)", cru_res->x,cru_res->y);
    }else{
        RCLCPP_INFO(client->get_logger(),"请求异常");
    }

    // 释放资源;
    rclcpp::shutdown();
    return 0;
}


  • 2
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值