假设工作文件夹在~/catkin_ws/src/learning_service下
第一步,创建一个srv文件夹
$ mkdir srv
第2步,定义自定义数据类型,在srv文件夹下创建.srv文件,假设定义一个Person.
$ cd srv
$ vi Person.srv
Person里面包含他的名字,年龄,性别,注意service要有request和response,
"- --"上面的部分是request, 下面是response
string name
uint8 age
uint8 sex
uint8 unknown = 0
uint8 male = 1
uint8 female = 2
---
string result
第3步, 编译message
首先需要添加依赖
(1)在learning_service下的package.xml中加入如下部分
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
(2)在learning_service下的CMakeLists.txt中加入如下部分
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
rospy
std_msgs
turtlesim
message_generation #added
)
....
add_service_files(FILES Person.srv) #added
generate_messages(DEPENDENCIES std_msgs) #added
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
....
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES learning_service
CATKIN_DEPENDS geometry_msgs roscpp rospy std_msgs turtlesim message_runtime #注释取消掉,加上message_runtime
# DEPENDS system_lib
)
(3)编译
$ cd ~/catkin_ws
$ catkin_make
可以看到编译出来的文件
$ cd ~/catkin_ws/devel/include/learning_service
$ ls
Person.h PersonRequest.h PersonResponse.h
其中Person.h包含了PersonRequest和PersonResponse, 用的时候只需要include Person.h
第4步, client端代码
进入src文件夹
$ cd ~/catkin_ws/src/learning_service/src
$ vi person_client.cpp
#include <ros/ros.h>
#include "learning_service/Person.h"
int main(int argc, char** argv) {
ros::init(argc, argv, "person_client");
ros::NodeHandle node;
//发现/show_person服务后,创建client, 连接/show_person的服务
ros::service::waitForService("/show_person");
ros::ServiceClient person_client = node.serviceClient<learning_service::Person>("/show_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 Person.h, Person的数据类型是learning_service::Person,
它有request和response两个部分,person_client.call(srv)调用时,它会发送出数据消息,并等待server的response,
等到response之后,输出srv.response.result, 注意ROS_INFO string类型的数据时,要转为c_str()
第5步, server端代码
$ cd ~/catkin_ws/src/learning_service/src
$ vi person_server.cpp
#include <ros/ros.h>
#include "learning_service/Person.h"
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::init(argc, argv, "person_server");
ros::NodeHandle n;
ros::ServiceServer person_service = n.advertiseService("/show_person", personCallback);
ROS_INFO("Ready to show person information");
ros::spin();
return 0;
}
service名为"/show_person", ros::spin()是无限循环,一直等client发来的request,
一旦有request, 就进入回调函数personCallback, 它的参数一个是request, 一个是response。
第6步,编译cpp文件
(1)在CMakeLists.txt中加入如下部分
#added-S
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)
#added-E
#############
## Install ##
#############
(2)编译
$ cd ~/catkin_ws
$ catkin_make
$ source devel/setup.bash
最后一步,运行
先运行server
$ rosrun learning_service person_server
[ INFO] [1642040930.719064479]: Ready to show person information
再运行client
$ rosrun learning_service person_client
[ INFO] [1642040973.332175599]: Call service to show person [name:Tom, age:20, sex:1]
[ INFO] [1642040973.334280244]: Show person result: OK
这时server端由于进入了回调函数,会出现如下信息
[ INFO] [1642040973.334187292]: Person: name:Tom age:20 sex:1
参考《古月居 ros》