如上图中的模型,此时希望在之前的服务器客户端的模型中发送人员信息可以通过service的方式,请求之后才去发送,同时在请求中使用自定义的服务数据类型learning_service::Person。
如何自定义服务数据
- 定义srv文件,在文件中定义服务数据的各个成员数据,在这里是Person.srv;
- 在package.xml中添加功能包依赖 <build_depend>message_generation</build_depend> <exec_depend>message_runtime</exec_depend>
- 在CMakeList.txt中添加编译选项
- 编译生成语言相关文件
Person.srv中---以上是request数据,---以下是response数据
string name
uint8 age
uint8 sex
uint8 unknown = 0
uint8 male = 1
uint8 female = 2
---
string result
在learning_service目录下创建srv文件夹后,添加该文件。
package.xml中添加依赖
CMakeList.txt中添加编译选项
find_package下加message_generaiton
添加service文件,用来说明生成头文件的依赖和产生消息类型所需的依赖
在catkin_package下添加依赖message_runtime
完成后保存编译,在该目录下产生了总体,请求和反馈的三个头文件。
至此service数据已经生成完毕,开始编写Client和Server端。
client端
/*
this program will ask for service named /show_person, service data type is learning_service::Person
*/
#include<ros/ros.h>
#include"learning_service/Person.h"
int main(int argc, char **argv)
{
//initiate ros node
ros::init(argc, argv, "person_client");
//create node handle
ros::NodeHandle node;
//create a client node after finding the /show_person service, connect the service named /show_person
ros::service::waitForService("show_person");
ros::ServiceClient person_client = node.serviceClient<learning_service::Person>("/show_person");
//initiate the request data of learning_service::Person
learning_service::Person srv;
srv.request.name = "Tom";
srv.request.age = 20;
srv.request.sex = learning_service::Person::Request::male;
//show the called service
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);
//show the calling result
ROS_INFO("Show person result : %s", srv.response.result.c_str());
return 0;
}
server端
/*
this program serves as the server
*/
#include<ros/ros.h>
#include"learning_service/Person.h"
//service callback function, input argument req, output argument res
bool personCallback(learning_service::Person::Request &req, learning_service::Person::Response &res)
{
//show request data
ROS_INFO("Person: name:%s age:%d sex:%d",req.name.c_str(), req.age, req.sex);
//set the callback data
res.result = "OK";
return true;
}
int main(int argc, char **argv)
{
//initiate ros node
ros::init(argc, argv, "person_server");
//create node handle
ros::NodeHandle n;
//create a server named /show_person, register the callback function
ros::ServiceServer person_service = n.advertiseService("/show_person", personCallback);
//waiting for the callback function
ROS_INFO("Ready to show person information.");
ros::spin();
return 0;
}
之后在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)
之后在catkin_ws目录下编译。运行两个节点后消息收发成功。
同时在所示目录下生成了服务器和客户端的shared library文件。
其中服务器和客户端都设置了等待,所以无论是服务器先启动还是客户端先启动,都可以等待另一方启动后完成request传输和service的进行,只是服务器启动后会持续等待客户端的rerquest,但是客户端会一次只产生一次消息传输。