服务消息通信是指请求服务的服务客户端与负责服务响应的服务服务器之间的同步双向服务消息通信,一个服务被分成服务服务器和服务客户端,其中服务服务器只在有请(request)的时候才响应(response),而服务客户端会在发送请求后接收响应。
与话题不同,服务是一次性消息通信。因此,当服务的请求和响应完成时,两个连接的节点将被断开。该服务通常被用作请求机器人执行特定操作时使用的命令,或者用于根据特定条件需要产生事件的节点。由于它是一次性的通信方式,又因为它在网络上的负载很小,所以它也被用作代替话题的手段,因此是一种非常有用的通信手段。
命令 | 详细说明 |
---|---|
rosservice list | 显示活动的服务信息 |
rosservice info [服务名称] | 显示指定服务的信息 |
rosservice type [服务名称] | 显示服务类型 |
rosservice find [服务类型] | 查找指定服务类型的服务 |
rosservice uri [服务名称] | 显示ROSRPC URI服务 |
rosservice args [服务名称] | 显示服务参数 |
rosservice call [服务名称] [参数] | 用输入的参数请求服务 |
ROS Master(管理者)
Server (服务端)
Client (客户端)
运行主节点
运行服务端
运行客户端
主节点向客户端发送服务端信息
客户端发送请求
服务端发送响应
需求描述:编写服务端和客户端文件,模拟打开、关闭开关的操作,服务端收到请求true(1)时打印 “开关打开” 的信息,收到请求false(0)时打印 “开关关闭” 的信息。
首先,这里创建了一个service_test的包,然后分别创建server.cpp(服务端)和client.cpp(客户端)两个文件。
#include "ros/ros.h"
#include "std_srvs/SetBool.h"
bool processRequest(std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response &res)
{
res.success = req.data;
if(req.data)
{
res.message = "开关已打开";
}
else
{
res.message = "开关已关闭";
}
ROS_INFO("状态切换为:%d --- %s", res.success, res.message.c_str());
return true;
}
int main(int argc, char **argv)
{
// 设置编码
setlocale(LC_ALL, "");
// 1.初始化ROS节点
ros::init(argc, argv, "server");
// 2.实例化ROS句柄
ros::NodeHandle nh;
// 3.实例化服务端对象
// 参数1为服务名称,参数2为处理请求的回调函数
ros::ServiceServer server = nh.advertiseService("service_chatter", processRequest);
ros::spin();
return 0;
}
#include "ros/ros.h"
#include "std_srvs/SetBool.h"
#include
int main(int argc, char **argv)
{
// 设置编码
setlocale(LC_ALL, "");
// 1.初始化ROS节点
// 参数3为节点名称,全局唯一
ros::init(argc, argv, "client");
// 2.实例化ROS句柄
ros::NodeHandle nh;
// 3.实例化客户端对象
// 参数1为服务名称
ros::ServiceClient client = nh.serviceClient<std_srvs::SetBool>("service_chatter");
// 4.定义请求数据
std_srvs::SetBool srv;
srv.request.data = atoll(argv[1]);
// 6.发送请求开关已打开
bool success = client.call(srv);
// 7.处理响应
if (success)
{
ROS_INFO("请求成功,收到反馈数据:%d --- %s", srv.response.success, srv.response.message.c_str());
}
else
{
ROS_ERROR("请求失败");
return 1;
}
return 0;
}
# 节点构建选项,配置可执行文件
add_executable(server src/server.cpp)
add_executable(client src/client.cpp)
# 节点构建选项,配置目标链接库
target_link_libraries(server
${catkin_LIBRARIES}
)
target_link_libraries(client
${catkin_LIBRARIES}
)
使用Ctrl+Shift+B进行编译,然后先使用roscore命令启动主节点。source下环境变量,然后运行服务端。在新终端source下环境变量,然后运行客户端,并附带请求参数。
话题的发布者和订阅者是没有启动顺序的要求的,因为消息是在循环发送,所以谁先启动谁后启动都能发送、接收消息。服务通信有所区别,需要先启动服务端,再启动客户端,否则会提示 “请求失败”。
我们可以使用消息阻塞函数来优化此问题,如果客户端先启动则一直阻塞,直到服务端启动后再继续执行。
在客户端发送请求之前添加下面的代码:
ros::service::waitForService("service_chatter");
ROS的服务类型可以在这里查看。
需求描述:客户端提交两个整数至服务端,服务端进行求和计算并响应结果给客户端。
srv 文件内的可用数据类型与 msg 文件一致,不同的是,srv文件中的数据分成两部分,使用 “- - -” 隔开,上面是请求数据,下面是响应数据。
首先,在service_test包中创建srv文件夹,然后,在文件夹中创建消息文件(AddTwoInts.srv)。
int64 A
int64 B
---
int64 Sum
<!-- 编译时依赖 -->
<build_depend>message_generation</build_depend>
<!-- 运行时依赖 -->
<exec_depend>message_runtime</exec_depend>
# catkin构建时依赖的组件包,前3个创建ROS包时已经自动生成了,这里添加了message_generation
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
# 配置srv源文件,FILES将引用当前功能包目录的srv目录中的*.srv文件,自动生成一个头文件(*.h)
add_service_files(
FILES
AddTwoInts.srv
)
# 生成消息时依赖于std_msgs
generate_messages(
DEPENDENCIES
std_msgs
)
# 运行时依赖,描述了库、catkin构建依赖项和系统依赖的功能包
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES topic_test
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
# DEPENDS system_lib
)
使用Ctrl+Shift+B进行编译,然后可以在/devel/service_test目录下看到自动生成的头文件AddTwoInts.h,此时便可以代后面的代码中进行引用了。
PS: 在修改代码之前,先在c_cpp_properties.json文件中添加下头文件路径,否则在代码中引用头文件时会出现找不到的情况。之前已经添加过的话,这里就不需要再重复添加了。
也可参考ROS WIKI中的代码示例。
下面我们在代码中使用自定义的srv来进行通信。
#include "ros/ros.h"
#include "service_test/AddTwoInts.h"
bool processRequest(service_test::AddTwoInts::Request &req,
service_test::AddTwoInts::Response &res)
{
res.Sum = req.A + req.B;
ROS_INFO("收到请求数据: x=%ld, y=%ld", (long int)req.A, (long int)req.B);
ROS_INFO("响应的计算结果为: [%ld]", (long int)res.Sum);
return true;
}
int main(int argc, char **argv)
{
// 设置编码
setlocale(LC_ALL, "");
// 1.初始化ROS节点
ros::init(argc, argv, "server");
// 2.实例化ROS句柄
ros::NodeHandle nh;
// 3.实例化服务端对象
// 参数1为服务名称,参数2为处理请求的回调函数
ros::ServiceServer server = nh.advertiseService("service_chatter", processRequest);
ros::spin();
return 0;
}
#include "ros/ros.h"
#include "service_test/AddTwoInts.h"
#include
int main(int argc, char **argv)
{
// 设置编码
setlocale(LC_ALL, "");
// 1.初始化ROS节点
// 参数3为节点名称,全局唯一
ros::init(argc, argv, "client");
// 这里的形参argc表示第二个形参数组argv中字符串的个数,即命令行传递的参数个数
// argv[0]:文件路径,/home/zbw/robot_test_ws/devel/lib/service_test/client
// argv[1]:传入的参数1,A
// argv[2]:传入的参数2,B
if (argc != 3)
{
ROS_ERROR("请提交两个整数");
return 1;
}
// 2.实例化ROS句柄
ros::NodeHandle nh;
// 3.实例化客户端对象
// 参数1为服务名称
ros::ServiceClient client = nh.serviceClient<service_test::AddTwoInts>("service_chatter");
// 等待服务端启动
ros::service::waitForService("service_chatter");
// 4.定义请求数据
service_test::AddTwoInts srv;
srv.request.A = atoll(argv[1]);
srv.request.B = atoll(argv[2]);
// 6.发送请求开关已打开
bool success = client.call(srv);
// 7.处理响应
if (success)
{
ROS_INFO("请求成功,收到反馈数据:%ld", (long int)srv.response.Sum);
}
else
{
ROS_ERROR("请求失败");
return 1;
}
return 0;
}
使用Ctrl+Shift+B进行编译,然后使用roscore命令启动主节点,source下环境变量,分别运行服务端和客户端即可看到通信数据的打印输出。
☝ ★★★ — 返回 《ROS机器人开发笔记汇总》总目录 — ★★★ ☝