ROS服务通信C++

创建工作空间

mkdir -p catkin_ws/src
cd catkin_ws
catkin_make

设置环境变量

source ./devel/setup.bash
source $ROS_PACKAGE_PATH

效果图

结构总览

友情提醒

每一步编辑完,执行一下 Ctrl+Shift+B进行编译,及时排查错误

准备工作

第一步:创建工作空间

配置:roscpp rospy std_msgs

// 快捷键 ctrl + shift + B 调用编译,选择:catkin_make:build
---
        {
		"version": "2.0.0",
		"tasks": [
			{
				"label": "catkin_make:debug", //代表提示的描述性信息
				"type": "shell",  //可以选择shell或者process,如果是shell代码是在shell里面运行一个命令,如果是process代表作为一个进程来运行
				"command": "catkin_make",//这个是我们需要运行的命令
				"args": [],//如果需要在命令后面加一些后缀,可以写在这里,比如-DCATKIN_WHITELIST_PACKAGES=“pac1;pac2”
				"group": {"kind":"build","isDefault":true},
				"presentation": {
					"reveal": "always"//可选always或者silence,代表是否输出信息
				},
				"problemMatcher": "$msCompile"
			}
		]
	}

src/sever_client/CMakeLists.txt

src/sever_client/src/package.xml

src/sever_client/srv/strings.srv

# 客户端请求时发送的两个字符串
string str1
string str2
---
# 服务器响应发送的数据
string res

src/sever_client/src/server.cpp

// 客户端请求时发送的两个字符串
#include "ros/ros.h"
#include "server_client/strings.h"
#include <string>
#include "std_msgs/String.h"
using namespace std;
using namespace std_msgs;

/*
1.包含头文件
服务端实现
*/

// bool 返回值由于标志是否处理成功
bool doStrings(server_client::strings::Request &request,
                              server_client::strings::Response &response)
{
    // 处理请求
    // string str1 = request.str1;
    // string str2 = request.str2; 
    string str1;
    str1 = request.str1;
    string str2; 
    str2=request.str2;
    ROS_INFO("服务器接收到的请求数据为:str1 = %s, str2 = %s",str1.c_str(), str2.c_str());

    // //组织响应
    // // static const string res = str1 + str2;
    // string res;
    // // sprintf(res, "%s%s", str1, str2);
    // res = str1 + str2;
    // // response.res = res;

   response.res = request.str1 + request.str2;
   // ROS_INFO("request: str1=%s, str2=%s", request.str1.c_str(), request.str2.c_str());
   ROS_INFO("服务器接发送的响应数据为: res = %s", response.res.c_str());

    // ros::spin();
    return true;
}

int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");
    // 2.初始化 ROS 节点
    ros::init(argc,argv,"strings_Server");
    // 3.创建 ROS 句柄
    ros::NodeHandle nh;
    // 4.创建 服务 对象
    ros::ServiceServer server = nh.advertiseService("strings",doStrings);
    ROS_INFO("服务端已经启动....");
    //     5.回调函数处理请求并产生响应
    //     6.由于请求有多个,需要调用 ros::spin()
    ros::spin();
    return 0;
}

devel/src/sever_client/src/client.cpp

// 客户端请求时发送的两个字符串

// 1.包含头文件
#include "ros/ros.h"
#include "server_client/strings.h"
#include <iostream>
#include "std_msgs/String.h"
using namespace std;
using namespace std_msgs;

int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");

    // 调用时动态传值,如果通过 launch 的 args 传参,需要传递的参数个数 +3
    if (argc != 3)
    // if (argc != 5)//launch 传参(0-文件路径 1传入的参数 2传入的参数 3节点名称 4日志路径)
    {
        ROS_ERROR("请提交两个字符串");
        return 1;
    }

    ROS_INFO("客户端已经启动....");

    // 2.初始化 ROS 节点
    ros::init(argc,argv,"strings_Client");
    // 3.创建 ROS 句柄
    ros::NodeHandle nh;
    // 4.创建 客户端 对象
    ros::ServiceClient client = nh.serviceClient<server_client::strings>("strings");
    //等待服务启动成功
    //方式1
    ros::service::waitForService("strings");
    //方式2
    // client.waitForExistence();
    // 5.组织请求数据
    server_client::strings ai;
    
    ai.request.str1 = argv[1];
    ai.request.str2 = argv[2];
    // cout << atoi(argv[1]) << ' ' << atoi(argv[2]);
    // ai.request.str1 = 'a';
    // ai.request.str2 = 'b';
    ROS_INFO("客户端发送的请求数据为:str1 = %s, str2 = %s",ai.request.str1.c_str(), ai.request.str2.c_str());
    
    // 6.发送请求,返回 bool 值,标记是否成功
    bool flag = client.call(ai);

    // 7.处理响应
    if (flag)
    {
        ROS_INFO("请求正常处理,响应结果: res = %s",ai.response.res.c_str());
    }
    else
    {
        ROS_ERROR("请求处理失败....");
        return 1;
    }

    return 0;
}

made by zyl