服务数据的定义与使用
服务数据的定义与使用
- 服务通信过程中服务的数据类型需要用户自己定义,与消息不同,节点并不提供标准服务类型
定义srv文件
创建
- .srv 文件只能放在 srv 目录下
roscd finaltest
mkdir srv
cd srv
touch Person.srv
# 注意Person首字母大写
- 自定义服务数据
string name
uint8 age
uint8 sex
uint8 unknown = 0
uint8 male = 1
uint8 female = 2
---
string result
配置
package.xml
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
注意,在构建时,其实只需要message_generation
,而在运行时,我们只需要message_runtime
CMakeLists.txt
- 将message_generation加在括号闭合前即可
find_package(catkin REQUIRED COMPONENTS
std_msgs
message_generation
)
- 表示要编译的服务类型文件,生成头文件
add_service_files(
FILES
Person.srv
)
- 添加生成消息的依赖,默认的时候要添加 std_msgs
generate_messages(
DEPENDENCIES
std_msgs
)
- 设置运行依赖
catkin_package(
CATKIN_DEPENDS message_runtime
)
注意,定义完srv文件后必须先编译生成头文件,然后再放Client和Server的源代码
Client
- 在 finaltest 包中 创建 person_client.cpp
#include <ros/ros.h>
#include "finaltest/Person.h"
int main(int argc, char** argv)
{
ros::init(argc, argv, "person_client"); // 初始化ROS节点
ros::NodeHandle node("~"); // 创建节点句柄
// 发现/spawn服务后,创建一个服务客户端,连接名为/spawn的service
ros::service::waitForService("/show_person");
ros::ServiceClient person_client = node.serviceClient<finaltest::Person>("/show_person");
// 初始化finaltest::Person的请求数据
finaltest::Person srv;
srv.request.name = "Tom";
srv.request.age = 20;
srv.request.sex = finaltest::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;
};
总结:
- 初始化ROS节点
- 创建一个Client实例
- 发布服务器请求数据
- 等待Server处理之后的应答结果
Server
- 在 finaltest 包中 创建 person_server.cpp
#include <ros/ros.h>
#include "finaltest/Person.h"
// service回调函数,输入参数req,输出参数res
bool personCallback(finaltest::Person::Request &req, finaltest::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;
}
总结:
- 初始化ROS节点
- 创建Server实例
- 循环等待服务请求,进入回调函数
- 在回调函数中完成服务功能的处理,并反馈应答数据
配置CMakeLists.txt
- 添加到CMakeLists.txt文件的底部
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)