创建一个request,里面包含学生的年龄性别姓名,发送给服务端,服务端再反馈response
如何自定义服务数据
- 定义srv文件
- 在package.xml中添加功能包依赖
- 在CMakeLists.txt添加编译选项
- 编译生成语言相关文件
1.定义srv文件
在learning_service下创建srv文件夹
在srv文件夹下创建Person.srv文件
string name
uint8 age
uint8 sex
uint8 unknown=0
uint8 male=1
uint8 female=2
---
string result
2.在package.xml中添加功能包依赖
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
3.在CMakeList.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)
4.在learing_service创建person_client.cpp和person_server.cpp文件
touch 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 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;
};
touch person_server.cpp
/**
* 该例程将执行/show_person服务,服务数据类型learning_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_service = n.advertiseService("/show_person", personCallback);
// 循环等待回调函数
ROS_INFO("Ready to show person informtion.");
ros::spin();
return 0;
}
5.编译
在catkin_ws文件下打开终端 输入
catkin_make
编译
6.验证
输入
roscore
rosrun learning_service person_client
rosrun learning_service person_server
当然,三个命令都是在不同终端下执行的。 每次发一次请求,客户端都会返回response,打印数据
结果