Service通讯机制

Service通讯分为client端server端

  • client端负责发送请求(Request)给server端
  • server端负责接收client端发送的请求数据。
  • server端收到数据后,根据请求数据和当前的业务需求,产生数据,将数据(Response)返回给client端

Service通讯的特点:

  • 同步数据访问
  • 具有响应反馈机制
  • 一个server多个client
  • 注重业务逻辑处理

Service通讯的关键点:

  • service的地址名称
  • client端访问server端的数据格式
  • server端响应client端的数据格式

Service通讯架构如下图:

ros_service

文本使用服务端接收数据端数据,并进行简单的加法运算后返回给客户端

首先在wssrc的目录下,使用catkin_create_pkg demo_service roscpp rospy rosmsg 创建 demo_service package

Server

C++ 版本

  1. src目录下创建一个server.cc文件,将以下代码粘贴到到该文件中
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
// 导入 ros 头文件
#include <ros/ros.h>

int main(int argc, char **argv) {
// 创建 ros 的节点名称
char node_name[] = "cpp_server";
// 初始化 ros 节点
ros::init(argc, argv, node_name);
// 创建一个节点对象
ros::NodeHandle node;
// todo 处理业务逻辑

// 进入一个简单的事件循环
ros::spin();
return 0;
}
  1. CMakeLists.txt 中添加 add_executabletarget_link_libraries
1
2
3
4
5
6
7
8
9
10
# 添加一个可执行程序
add_executable(
demo_server
src/server.cc
)
# 添加该可执行程序的依赖库
target_link_libraries(
demo_server
${catkin_LIBRARIES}
)
  1. 创建 Server 对象

    1. 导入要发送的消息的头文件
    1
    #include "roscpp_tutorials/TwoInts.h"
    1. 创建对象,并发送消息
    1
    2
    3
    4
    5
    // 创建 service 名称
    char service_name[] = "demo_service";
    // 创建一个 server
    const ros::ServiceServer &server =
    node.advertiseService(service_name, serviceCallback);
    1. 创建 serviceCallback 回调函数
    1
    2
    3
    4
    5
    6
    7
    bool serviceCallback(roscpp_tutorials::TwoInts::Request &request,
    roscpp_tutorials::TwoInts::Response &response) {
    // 返回值 bool:true代表成功响应,false代表拒绝响应
    // 可根据业务实际情况返回相应数据,本例就不做false处理了
    response.sum = request.a + request.b;
    return true;
    }
  2. 编译该节点,在工作空间目录下

1
catkin_make

Python 版本

  1. package 目录下创建一个名为 scripts 的文件夹
  2. 创建一个名为 server.py 的文件,将以下代码添加到该文件中
1
2
3
4
5
6
7
8
9
10
11
12
13
14
#!/usr/bin/env python
# coding: utf-8

# 导入 rospy 依赖
import rospy

if __name__ == "__main__":
# 节点名称
node_name = "py_server"
# 初始化 ros 节点
rospy.init_node(node_name)
# todo 处理业务逻辑
# 开启 ros 运行时循环
rospy.spin()
  1. 创建 Server 对象

    1. 导入要发送的消息的头文件
    1
    from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse
    1. 创建对象,并发送消息
    1
    2
    3
    4
    # 创建 Service 名称
    service_name = "demo_service"
    # 创建 server
    server = rospy.Service(service_name, AddTwoInts, serviceCallback)
    1. 创建 serviceCallback 回调函数
    1
    2
    3
    4
    5
    6
    7
    def serviceCallback(request=AddTwoIntsRequest()):
    response = AddTwoIntsResponse()
    response.sum = request.a + request.b
    # 返回一个对应类型的 response 代表成功响应
    # 返回空值,代表拒绝响应
    # 在 Python 中可以更加灵活的使用返回数据,此例返回 a+b 也可以达到效果
    return response
  2. 给 server.py 赋予可执行权限

1
chmod a+x src/demo_service/scripts/server.py

使用rosservice调试

  1. 将当前工作空间的环境变量添加到bashzsh
1
2
3
# 根据使用不同的 shell 使用不同的环境变量,两者选其一
source devel/setup.bash # 使用 bash
source devel/setup.zsh # 使用 zsh
  1. 运行 server 程序

    1. c++ 程序
    1
    rosrun demo_service demo_server
    1. python 程序
    1
    rosrun demo_service server.py
  2. 使用rosservice call /demo_service "a: 2 b: 1"

    • 响应数据 sum: 3

使用 rqt_service_caller 调试

前两步与上面相同,然后使用rosrun rqt_service_caller rqt_service_caller

  1. 选择对应的service,本例为demo_service
  2. 填充数据后按右上角的call发送
  3. 示意图如下所示

rqt_service_caller

总结

  1. 使用第三方的srv与msg类似,这里就不做赘述,配置方法与msg一样,详情可见
  2. 在回调函数的使用中,Python 与 C++ 的参数不一样,C++通过返回bool值判断是否成功响应,Python通过是否返回空值判断是否成功响应。
  3. C++使用node.advertiseService创建server
  4. Python使用rospy.Service创建server

Client

C++ 版本

  1. src目录下创建一个client.cc文件,将以下代码粘贴到到该文件中
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
// 导入 ros 头文件
#include <ros/ros.h>

int main(int argc, char **argv) {
// 创建 ros 的节点名称
char node_name[] = "cpp_client";
// 初始化 ros 节点
ros::init(argc, argv, node_name);
// 创建一个节点对象
ros::NodeHandle node;

// todo 处理业务逻辑

// 进入一个简单的事件循环
ros::spin();
return 0;
}
  1. CMakeLists.txt 中添加 add_executabletarget_link_libraries
1
2
3
4
5
6
7
8
9
10
# 添加一个可执行程序
add_executable(
demo_client
src/client.cc
)
# 添加该可执行程序的依赖库
target_link_libraries(
demo_client
${catkin_LIBRARIES}
)
  1. 创建 Client 对象

    1. 导入要发送的消息的头文件
    1
    #include "roscpp_tutorials/TwoInts.h"
    1. 创建对象,并发送消息
    1
    2
    3
    4
    5
    6
    7
    8
    9
    10
    11
    12
    13
    14
    15
       // 创建 service 名称
    char service_name[] = "demo_service";
    // 创建 Client
    ros::ServiceClient client =
    node.serviceClient<roscpp_tutorials::TwoInts>(service_name);
    // 创建一个Request 和 Response
    roscpp_tutorials::TwoInts::Request request;
    roscpp_tutorials::TwoInts::Response response;
    request.a = 1, request.b = 2;
    if (client.call(request, response)) { // 判断是否响应
    // 获取到响应的数据
    std::cout << response.sum << std::endl;
    } else {
    std::cout << "服务器 拒绝" << std::endl;
    }
  2. 编译该节点,在工作空间目录下

1
catkin_make

Python 版本

  1. package 目录下创建一个名为 scripts 的文件夹
  2. 创建一个名为 client.py 的文件,将以下代码添加到该文件中
1
2
3
4
5
6
7
8
9
10
11
12
13
14
#!/usr/bin/env python
# coding: utf-8

# 导入 rospy 依赖
import rospy

if __name__ == "__main__":
# 节点名称
node_name = "py_client"
# 初始化 ros 节点
rospy.init_node(node_name)
# todo 处理业务逻辑
# 开启 ros 运行时循环
rospy.spin()
  1. 创建 Client 对象

    1. 导入要发送的消息的头文件
    1
    from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse
    1. 创建对象,并发送消息
    1
    2
    3
    4
    5
    6
    7
    8
    9
    10
    11
    12
    # 创建 Service 名称
    service_name = "demo_service"
    # 创建 server
    client = rospy.ServiceProxy(service_name, AddTwoInts)
    # 创建 Request
    request = AddTwoIntsRequest()
    request.a, request.b = 1, 2
    try:
    response = client.call(request)
    print(response.sum)
    except rospy.ServiceException as error: # 服务器拒绝响应的错误
    print("服务器拒绝响应")
  2. 给 client.py 赋予可执行权限

1
chmod a+x src/demo_service/scripts/client.py

调试

运行之前写好的 Server 端,分别 C++ 程序和 Python 程序,即可。

  1. C++ 程序
1
rosrun demo_service demo_client
  1. python 程序
1
rosrun demo_service client.py

总结

  1. C++ 创建 Client 的方法为node.serviceClient<srv_type>(srv_name)
  2. Python 创建的 Client 的方法为rospy.ServiceProxy(srv_name, srv_type)
  3. C++ 以call的返回值的Yes,No来判断服务器是否响应
  4. Python 使用 try...except判断是是否是rospy.ServiceException类型来判断服务器是否成功响应

代码块

C++

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
"ros_create_server": {
"prefix": "ros_create_server",
"body": [
"// todo 填写 service 的类型",
"#include \"${1:service_class}\"",
"",
"// todo 填写 service 的类型",
"bool serviceCallback(${2:service_class}::Request &request,",
" ${2:service_class}::Response &response) {",
" // TODO 服务端需要处理的业务逻辑",
" // 返回值 bool:true代表成功响应,false代表拒绝响应",
" return true;",
"}",
"",
"// 创建 service 名称",
"// todo 填写 service_name",
"char service_name[] = \"${3:service_name}\";",
"// 创建一个 server",
"const ros::ServiceServer &server =",
" node.advertiseService(service_name, serviceCallback);",
]
}
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
"ros_create_client": {
"prefix": "ros_create_client",
"body": [
"// todo 填写 service 的类型",
"#include \"${1:service_class}\"",
"",
"// todo 填写 service_name",
"char service_name[] = \"${2:service_name}\";",
"// 创建 Client",
"ros::ServiceClient client =",
" node.serviceClient<${3:service_class}>(service_name);",
"// 创建一个Request 和 Response",
"${3:service_class}::Request request;",
"${3:service_class}::Response response;",
"if (client.call(request, response)) { // 判断是否响应",
" // 获取到响应的数据",
" // todo 进行获取到数据之后的业务逻辑处理",
"} else {",
" std::cout << \"服务器 拒绝\" << std::endl;",
"}",
]
}

Python

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
"ros_create_server": {
"prefix": "ros_create_server",
"body": [
"# todo 填写 service 的类型",
"from ${1}.srv import ${2}, ${2}Request, ${2}Response",
"",
"",
"def serviceCallback(request=${2}Request()):",
" response = ${2}Response()",
" # 返回一个对应类型的 response 代表成功响应",
" # 返回空值,代表拒绝响应",
" return response",
"",
"# 创建 Service 名称",
"# todo 填写一个 service 的名称",
"service_name = \"${3:service_name}\"",
"# 创建 server",
"server = rospy.Service(service_name, ${2}, serviceCallback)",
]
},
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
"ros_create_client": {
"prefix": "ros_create_client",
"body": [
"# todo 填写 service 的类型",
"from ${1}.srv import ${2}, ${2}Request, ${2}Response",
"",
"# 创建 Service 名称",
"service_name = \"${3}\"",
"# 创建 Server",
"client = rospy.ServiceProxy(service_name, ${2})",
"# 创建 Request",
"request = ${2}Request()",
"request.a, request.b = 1, 2",
"try:",
" response = client.call(request)",
" print(response.sum)",
"except rospy.ServiceException as error: # 服务器拒绝响应的错误",
" print(\"服务器拒绝响应\")",
]
}

附录

Server

C++

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
// 导入 ros 头文件
#include "roscpp_tutorials/TwoInts.h"
#include <ros/ros.h>

bool serviceCallback(roscpp_tutorials::TwoInts::Request &request,
roscpp_tutorials::TwoInts::Response &response) {
// 返回值 bool:true代表成功响应,false代表拒绝响应
// 可根据业务实际情况返回相应数据,本例就不做false处理了
response.sum = request.a + request.b;
return true;
}

int main(int argc, char **argv) {
// 创建 ros 的节点名称
char node_name[] = "cpp_server";
// 初始化 ros 节点
ros::init(argc, argv, node_name);
// 创建一个节点对象
ros::NodeHandle node;
// 创建 service 名称
char service_name[] = "demo_service";
// 创建一个 server
const ros::ServiceServer &server =
node.advertiseService(service_name, serviceCallback);

// 进入一个简单的事件循环
ros::spin();
return 0;
}

Python

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
#!/usr/bin/env python
# coding: utf-8

# 导入 rospy 依赖
import rospy
from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse


def serviceCallback(request=AddTwoIntsRequest()):
response = AddTwoIntsResponse()
response.sum = request.a + request.b
# 返回一个对应类型的 response 代表成功响应
# 返回空值,代表拒绝响应
# 在 Python 中可以更加灵活的使用返回数据,此例返回 a+b 也可以达到效果
return response


if __name__ == "__main__":
# 节点名称
node_name = "py_server"
# 初始化 ros 节点
rospy.init_node(node_name)
# 创建 Service 名称
service_name = "demo_service"
# 创建 server
server = rospy.Service(service_name, AddTwoInts, serviceCallback)
# 开启 ros 运行时循环
rospy.spin()

Client

C++

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
// 导入 ros 头文件
#include "roscpp_tutorials/TwoInts.h"
#include <ros/ros.h>
int main(int argc, char **argv) {
// 创建 ros 的节点名称
char node_name[] = "cpp_client";
// 初始化 ros 节点
ros::init(argc, argv, node_name);
// 创建一个节点对象
ros::NodeHandle node;

// 创建 service 名称
char service_name[] = "demo_service";
// 创建 Client
ros::ServiceClient client =
node.serviceClient<roscpp_tutorials::TwoInts>(service_name);
// 创建一个Request 和 Response
roscpp_tutorials::TwoInts::Request request;
roscpp_tutorials::TwoInts::Response response;
request.a = 1, request.b = 2;
if (client.call(request, response)) { // 判断是否响应
// 获取到响应的数据
std::cout << response.sum << std::endl;
} else {
std::cout << "服务器 拒绝" << std::endl;
}
// 进入一个简单的事件循环
ros::spin();
return 0;
}

Python

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
#!/usr/bin/env python
# coding: utf-8

# 导入 rospy 依赖
import rospy
from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse

if __name__ == "__main__":
# 节点名称
node_name = "py_client"
# 初始化 ros 节点
rospy.init_node(node_name)
# 创建 Service 名称
service_name = "demo_service"
# 创建 server
client = rospy.ServiceProxy(service_name, AddTwoInts)
# 创建 Request
request = AddTwoIntsRequest()
request.a, request.b = 1, 2
try:
response = client.call(request)
print(response.sum)
except rospy.ServiceException as error: # 服务器拒绝响应的错误
print("服务器拒绝响应")

# 开启 ros 运行时循环
rospy.spin()

评论