学习ROS基础的电子笔记,摘录自各类ROS基础课程,文末会附上本次内容参考的相关课程视频链接。
实现一个服务模型:
(1)client端发送显示某个人信息的的request,同时将该人的信息以learning_service::Person的数据格式发出去;
(2)server端通过话题/show_person响应client端的request;
1. 自定义服务数据
- 定义srv数据
// 创建新的文件夹
cd ~/catkin_ws/src/learning_service
mkdir srv
vim srv/Person.srv
string name
uint8 age
uint8 sex
uint8 unknown = 0
uint8 male = 1
uint8 female = 2
---
string result
ROS规定,三个横线是分割线,其上为request的消息格式,其下为response的消息格式。
- 在package.xml中添加功能包依赖
vim ~/catkin_ws/src/learning_service/package.xml
<build_export_depend>message_generation</build_export_depend>
<exec_depend>message_runtime</exec_depend>
- 在CMakeLists.txt中添加编译选项
vim ~/catkin_ws/src/learning_service/CMakeLists.txt
find_package(catkin REQUIRED COMPONENTS
...
message_generation
)
add_service_files(
FILES
# Service1.srv
# Service2.srv
Person.srv
)
generate_messages(
DEPENDENCIES
# geometry_msgs
std_msgs
)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES learning_service
CATKIN_DEPENDS geometry_msgs roscpp rospy turtlesim message_runtime
# DEPENDS system_lib
)
cd ~/catkin_ws
catkin_make
出现如下结果,证明编译成功:
编译成功后,与learning_topic不同的是,devel/include/learning_service目录下有三个文件,Person.h; PersonRequest.h; PersonResponse.h 文件,这是因为我们在编写srv文件时就用分割线分出来request与response消息格式。
2. 编写person_client.cpp文件
vim ~/catkin_ws/src/learning_service/src/person_client.cpp
/**
* 该例程将请求/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 n ;
// 发现/show_person服务后,创建一个服务客户端,连接名为/show_person的service
ros :: service :: waitForService("/show_person") ;
ros :: ServiceClient person_client = n.serviceClient<learning_service :: Person>("/show_person") ;
// 初始化learning_service :: Person的请求数据
learning_service :: Person srv ;
srv.request.name = "Alice" ;
srv.request.age = 20 ;
srv.request.sex = learning_service :: Person :: Request :: female ;
// 请求服务调用
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 ;
}
3. 编写person_server.cpp文件
vim ~/catkin_ws/src/learning_service/src/person_server.cpp
/**
* 该例程将执行/show_person服务,服务数据类型learing_service::Person
*/
#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_server = n.advertiseService("/show_person", personCallback) ;
// 循环等待回调函数
ROS_INFO("Ready to show person information.") ;
ros :: spin() ;
return 0 ;
}
4. 配置服务器、客户端代码编译规则
vim ~/catkin_ws/src/learning_service/CMakeLists.txt
add_executable(person_server src/person_server.cpp)
add_executable(person_client src/person_client.cpp)
target_link_libraries(person_server
${catkin_LIBRARIES}
)
target_link_libraries(person_client
${catkin_LIBRARIES}
)
add_dependencies(person_server ${PROJECT_NAME}_gencpp)
add_dependencies(person_client ${PROJECT_NAME}_gencpp)
// 编译程序
cd ~/catkin_ws
catkin_make
5.执行程序
// terminal1
roscore
// terminal2
source ~/catkin_ws/devel/setup.bash
rosrun learning_service person_server
// terminal3
source ~/catkin_ws/devel/setup.bash
rosrun learning_service person_client
运行结果如下:
参考课程: ROS入门21讲(古月居-第15讲)