ROS(五)----服务通信

服务通信,通过服务端客户端 ,请求响应的同步模式进行通信。

一、工程结构

 

 二、自定义srv

 

 使用 ---进行分割

上边为 :resquest

下边为:response

添加.srv 文件后 ,CMakeLists.txt

add_service_files(FILES
PassWord.srv
)
generate_messages(DEPENDENCIES
std_msgs
)
 

编译后:

 

 

 

 

 三、 服务端 和 客户端示例

服务端

#include"ros/ros.h"
#include"book_service/PassWord.h"
#include <cstdlib>
using namespace std;

// server callback function
bool serverCallback(book_service::PassWord::Request &req, book_service::PassWord::Response &res)
{
    res.result = (req.password==741963)? true:false;
    return true;
}

int main(int argc,char** argv)
{
    // initial node and name
    ros::init(argc, argv, "server_node");
    // create nodeHandle
    ros::NodeHandle nh;
    ros::ServiceServer serv = nh.advertiseService("pswserver",&serverCallback);  // 创建服务器 指定回调函数

    ros::spin();
    return 0;
}

客户端

#include "ros/ros.h"
#include "book_service/PassWord.h"
#include <cstdlib>

using namespace std;

int main(int argc,char** argv)
{
    // initial node and name
    ros::init(argc,argv,"node_client");

    ros::NodeHandle nh;
    ros::ServiceClient client = nh.serviceClient<book_service::PassWord>("pswserver",100);
    book_service::PassWord srv; //服务信息 .srv

    if(argc < 2)
    {
        ROS_INFO("input error!");
        return 0;
    }
    srv.request.password=atoi(argv[1]);
    
    if(client.call(srv))
    {
        ROS_INFO("client connect success!");
        if(srv.response.result)
        {
            ROS_INFO("password is correct!!");
        }
        else
        {
            ROS_INFO("password is error!!");
        }
    }
    else
    {
        ROS_INFO("client connect fail  !!!!!!");
    }
    return 0;
}

 

posted on 2020-03-05 13:14  feihu_h  阅读(343)  评论(0编辑  收藏  举报

导航