Service通讯机制
Service通讯分为client端
和server端
。
client端
负责发送请求(Request)给server端
。server端
负责接收client端
发送的请求数据。server端
收到数据后,根据请求数据和当前的业务需求,产生数据,将数据(Response)返回给client端
。
Service通讯的特点:
- 同步数据访问
- 具有响应反馈机制
- 一个server多个client
- 注重业务逻辑处理
Service通讯的关键点:
service
的地址名称client端
访问server端
的数据格式server端
响应client端
的数据格式
Service通讯架构如下图:
文本使用服务端接收数据端数据,并进行简单的加法运算后返回给客户端
首先在
ws
的src
的目录下,使用catkin_create_pkg demo_service roscpp rospy rosmsg
创建demo_service
package
Server
C++ 版本
- 在
src
目录下创建一个server.cc
文件,将以下代码粘贴到到该文件中
1 |
// 导入 ros 头文件 |
- 在
CMakeLists.txt
中添加add_executable
和target_link_libraries
1 |
# 添加一个可执行程序 |
-
创建
Server
对象- 导入要发送的消息的头文件
1
- 创建对象,并发送消息
1
2
3
4
5// 创建 service 名称
char service_name[] = "demo_service";
// 创建一个 server
const ros::ServiceServer &server =
node.advertiseService(service_name, serviceCallback);- 创建
serviceCallback
回调函数
1
2
3
4
5
6
7bool serviceCallback(roscpp_tutorials::TwoInts::Request &request,
roscpp_tutorials::TwoInts::Response &response) {
// 返回值 bool:true代表成功响应,false代表拒绝响应
// 可根据业务实际情况返回相应数据,本例就不做false处理了
response.sum = request.a + request.b;
return true;
} -
编译该节点,在工作空间目录下
1 |
catkin_make |
Python 版本
- 在
package
目录下创建一个名为scripts
的文件夹 - 创建一个名为
server.py
的文件,将以下代码添加到该文件中
1 |
#!/usr/bin/env python |
-
创建
Server
对象- 导入要发送的消息的头文件
1
from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse
- 创建对象,并发送消息
1
2
3
4# 创建 Service 名称
service_name = "demo_service"
# 创建 server
server = rospy.Service(service_name, AddTwoInts, serviceCallback)- 创建
serviceCallback
回调函数
1
2
3
4
5
6
7def serviceCallback(request=AddTwoIntsRequest()):
response = AddTwoIntsResponse()
response.sum = request.a + request.b
# 返回一个对应类型的 response 代表成功响应
# 返回空值,代表拒绝响应
# 在 Python 中可以更加灵活的使用返回数据,此例返回 a+b 也可以达到效果
return response -
给 server.py 赋予可执行权限
1 |
chmod a+x src/demo_service/scripts/server.py |
使用rosservice调试
- 将当前工作空间的环境变量添加到
bash
或zsh
中
1 |
# 根据使用不同的 shell 使用不同的环境变量,两者选其一 |
-
运行 server 程序
- c++ 程序
1
rosrun demo_service demo_server
- python 程序
1
rosrun demo_service server.py
-
使用
rosservice call /demo_service "a: 2 b: 1"
- 响应数据 sum: 3
使用 rqt_service_caller 调试
前两步与上面相同,然后使用rosrun rqt_service_caller rqt_service_caller
- 选择对应的
service
,本例为demo_service
- 填充数据后按右上角的
call
发送 - 示意图如下所示
总结
- 使用第三方的srv与msg类似,这里就不做赘述,配置方法与msg一样,详情可见
- 在回调函数的使用中,Python 与 C++ 的参数不一样,C++通过返回bool值判断是否成功响应,Python通过是否返回空值判断是否成功响应。
- C++使用
node.advertiseService
创建server
- Python使用
rospy.Service
创建server
Client
C++ 版本
- 在
src
目录下创建一个client.cc
文件,将以下代码粘贴到到该文件中
1 |
// 导入 ros 头文件 |
- 在
CMakeLists.txt
中添加add_executable
和target_link_libraries
1 |
# 添加一个可执行程序 |
-
创建
Client
对象- 导入要发送的消息的头文件
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;
} -
编译该节点,在工作空间目录下
1 |
catkin_make |
Python 版本
- 在
package
目录下创建一个名为scripts
的文件夹 - 创建一个名为
client.py
的文件,将以下代码添加到该文件中
1 |
#!/usr/bin/env python |
-
创建
Client
对象- 导入要发送的消息的头文件
1
from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse
- 创建对象,并发送消息
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("服务器拒绝响应") -
给 client.py 赋予可执行权限
1 |
chmod a+x src/demo_service/scripts/client.py |
调试
运行之前写好的 Server 端,分别 C++
程序和 Python
程序,即可。
- C++ 程序
1 |
rosrun demo_service demo_client |
- python 程序
1 |
rosrun demo_service client.py |
总结
- C++ 创建 Client 的方法为
node.serviceClient<srv_type>(srv_name)
- Python 创建的 Client 的方法为
rospy.ServiceProxy(srv_name, srv_type)
- C++ 以call的返回值的Yes,No来判断服务器是否响应
- Python 使用
try...except
判断是是否是rospy.ServiceException
类型来判断服务器是否成功响应
代码块
C++
1 |
"ros_create_server": { |
1 |
"ros_create_client": { |
Python
1 |
"ros_create_server": { |
1 |
"ros_create_client": { |
附录
Server
C++
1 |
// 导入 ros 头文件 |
Python
1 |
#!/usr/bin/env python |
Client
C++
1 |
// 导入 ros 头文件 |
Python
1 |
#!/usr/bin/env python |