目录
一、服务模型(客户端/服务器)
二、自定义服务数据
1. 定义srv文件
string name
uint8 age
uint8 sex
uint8 unknow = 0
uint8 male = 1
uint8 female = 2
---
string result
三个横线作为一个区分,上面是request,下面是response;
创建完之后如下所示
2. 在package.xml中添加功能包依赖
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
如下图所示:
3. 在CMakeLists.txt添加编译选项
- find_package(...... message_generation)
- add_service_files(FILES Person.srv)
- generate_messages(DEPENDENCIES std_msgs)
- catkin_package(...... message_runtime)
4. 编译生成语言相关文件
在catkin_ws目录下进行编译,最后生成的了三个头文件,位于catkin_ws/devel/include/learning_service
(生成三个头文件是因为srv文件上面会生成一个文件,下面也会生成一个头文件,最后整体装再生成一个头文件位于Person.h内)
接下来通过使用客户端和服务器来验证服务模型
客户端的代码如下:
* 该例程将请求/show_person服务,服务数据类型learning_service::Person
*/
#include <ros/ros.h>
#include "learning_service/Person.h"
int main(int argc, char** argv)
{
// 初始化ROS节点
ros::init(argc, argv, "person_client");
// 创建节点句柄
ros::NodeHandle node;
// 发现/spawn服务后,创建一个服务客户端,连接名为/spawn的service
ros::service::waitForService("/show_person");
ros::ServiceClient person_client = node.serviceClient<learning_service::Person>("/show_person");
// 初始化learning_service::Person的请求数据
learning_service::Person srv;
srv.request.name = "Tom";
srv.request.age = 20;
srv.request.sex = learning_service::Person::Request::male;
// 请求服务调用
ROS_INFO("Call service to show person[name:%s, age:%d, sex:%d]",
srv.request.name.c_str(), srv.request.age, srv.request.sex);
person_client.call(srv);
// 显示服务调用结果
ROS_INFO("Show person result : %s", srv.response.result.c_str());
return 0;
};
服务器的代码如下:
#include <ros/ros.h>
#include "learning_service/Person.h"
// service回调函数,输入参数req,输出参数res
bool personCallback(learning_service::Person::Request &req,
learning_service::Person::Response &res)
{
// 显示请求数据
ROS_INFO("Person: name:%s age:%d sex:%d", req.name.c_str(), req.age, req.sex);
// 设置反馈数据
res.result = "OK";
return true;
}
int main(int argc, char **argv)
{
// ROS节点初始化
ros::init(argc, argv, "person_server");
// 创建节点句柄
ros::NodeHandle n;
// 创建一个名为/show_person的server,注册回调函数personCallback
ros::ServiceServer person_service = n.advertiseService("/show_person", personCallback);
// 循环等待回调函数
ROS_INFO("Ready to show person informtion.");
ros::spin();
return 0;
}
5. 配置服务器/客户端代码编译规则
配置CMakeLists.txtx中的编译:
- 设置需要编译的代码和生成的可知悉文件;
- 设置链接库;
- 添加依赖项
add_executable(person_server src/person_server.cpp)
target_link_libraries(person_server ${catkin_LIBRARIES})
add_dependencies(person_server ${PROJECT_NAME}_gencpp)
add_executable(person_client src/person_client.cpp)
target_link_libraries(person_client ${catkin_LIBRARIES})
add_dependencies(person_client ${PROJECT_NAME}_gencpp)
编译后的结果可以在 catkin_ws/devel/include/learning_service中
6. 编译并运行程序
运行后客户端每次发送数据,服务器会收到,而且服务器会给客户端回复一个OK
7. Python文件
客户端程序如下:
import sys
import rospy
from learning_service.srv import Person, PersonRequest
def person_client():
# ROS节点初始化
rospy.init_node('person_client')
# 发现/spawn服务后,创建一个服务客户端,连接名为/spawn的service
rospy.wait_for_service('/show_person')
try:
person_client = rospy.ServiceProxy('/show_person', Person)
# 请求服务调用,输入请求数据
response = person_client("Tom", 20, PersonRequest.male)
return response.result
except rospy.ServiceException, e:
print "Service call failed: %s"%e
if __name__ == "__main__":
#服务调用并显示调用结果
print "Show person result : %s" %(person_client())
服务器程序如下:
import rospy
from learning_service.srv import Person, PersonResponse
def personCallback(req):
# 显示请求数据
rospy.loginfo("Person: name:%s age:%d sex:%d", req.name, req.age, req.sex)
# 反馈数据
return PersonResponse("OK")
def person_server():
# ROS节点初始化
rospy.init_node('person_server')
# 创建一个名为/show_person的server,注册回调函数personCallback
s = rospy.Service('/show_person', Person, personCallback)
# 循环等待回调函数
print "Ready to show person informtion."
rospy.spin()
if __name__ == "__main__":
person_server()