ROS 7: 服务数据自定义
从上一篇文章中,简单介绍了服务端以及客户端的代码实现。这里主要描述自己定义服务的数据类型,并且来使用它。我们仍然使用宝可梦的例子来写代码。
在前面自定义topic中,topic会一直发数据。我们现在改善一下上次的宝可梦例子,让它只有在request的时候才会发数据
在自定义消息的那一章节中,我们使用
*.msg
的文件来存储,在服务数据自定义中也是类似的,我们使用*.srv
文件在自定义数据类型 可以参考自定义消息的笔记: ROS5
一、定义srv文件,编译头文件
*.msg
文件与*.srv
文件的区别在于,由于服务数据除了要定义request,还需要定义response。可以参考ROS6.定义消息类型的时候,数据定义需要用---
三横线区分开来。
在功能包里新建一个文件夹srv
,touch一个*.srv
文件,并输入定义的内容。
这里在learn_server功能包下新建一个srv文件夹,把Pokemon.srv放在这个目录下
string name
string type
uint8 gender
uint8 unknown = 0
uint8 male = 1
uint8 female = 2
---
string result
修改CMakeLists.txt,在第十行find_package处修改,主要是最后一行加上message_generation
这个功能包依赖
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
rospy
std_msgs
turtlesim
message_generation
)
然后在CMakeLists.txt再加上以下内容,让编译器知道要根据哪个srv文件产生头文件
add_service_files(FILES Pokemon.srv)
generate_messages(DEPENDENCIES std_msgs)
然后在CMakeLists.txt加上以下内容,添加编译依赖
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES learn_server
CATKIN_DEPENDS geometry_msgs roscp rospy std_msgs turtlesim message_runtime
# DEPENDS system_lib
)
最后再package.xml文件添加以下依赖描述:
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
在工作空间根目录下,使用catkin_make
编译头文件
编译完成之后,在工作空间的devel/include/learn_server目录下,可以看到三个编译完成的头文件:
-
Pokemon.h:会包含以下两个头文件,加载这一个就足矣。
-
PokemonRequest.h
-
PokemonResponse.h
二、代码实现
c++实现
1、服务端实现
导入头文件
#include <ros/ros.h>
#include "learn_server/Pokemon.h"
写主函数
int main(int argc, char **argv)
{
// ROS节点初始化
ros::init(argc, argv, "pokemon_server");
ros::NodeHandle ser_pokemon_node;
// 创建一个叫做/pokemon_show的server,注册回调函数Callback
ros::ServiceServer pokemon_server = ser_pokemon_node.advertiseService("/pokemon_show", Callback);
// 循环等待回调函数
ROS_INFO("Ready to show pokemon infomation");
ros::spin();
return 0;
}
然后就是写好回调函数
// service回调函数,输入参数req,输出参数res
bool Callback(learn_server::Pokemon::Request &req,learn_server::Pokemon::Response &res)
{
// 显示请求数据
ROS_INFO("Pokemon: name:%s type:%s gender:%d", req.name.c_str(), req.type.c_str(), req.gender);
// 设置反馈数据
res.result = "Pokemon response. Done";
return true;
}
2、客户端实现
#include <ros/ros.h>
#include "learn_server/Pokemon.h"
int main(int argc,char **argv){
ros::init(argc,argv,"pokemon_client");
ros::NodeHandle cli_pokemon_node;
// 发现/pokemon_show服务后,创建一个服务客户端,连接名为/pokemon_show的service
ros::service::waitForService("/pokemon_show");
ros::ServiceClient pokemon_client = cli_pokemon_node.serviceClient<learn_server::Pokemon>("/pokemon_show");
// 初始化learn_server::Pokemon的请求数据
learn_server::Pokemon srv;
srv.request.name = "Pikachu";
srv.request.type = "electric";
srv.request.gender = learn_server::Pokemon::Request::male;
// 请求服务调用
ROS_INFO("Call service [name:%s, age:%s, sex:%d]",
srv.request.name.c_str(), srv.request.type.c_str(), srv.request.gender);
pokemon_client.call(srv);
// 显示服务调用结果
ROS_INFO("Result : %s", srv.response.result.c_str());
return 0;
}
3、编译运行
在CMakeLists中增加以下内容,告知编译器相关编译规则:
add_executable(ser_pokemon src/ser_pokemon.cpp)
target_link_libraries(ser_pokemon ${catkin_LIBRARIES})
add_dependencies(ser_pokemon ${PROJECT_NAME}_gencpp)
add_executable(cli_pokemon src/cli_pokemon.cpp)
target_link_libraries(cli_pokemon ${catkin_LIBRARIES})
add_dependencies(cli_pokemon ${PROJECT_NAME}_gencpp)
然后在工作空间使用catkin_make
编译即可运行
在运行代码之前记得先在待运行的终端执行source devel/setup.bash
指令,修改环境变量,rosrun才能读到功能包下的可执行文件。
python实现
1、服务端实现
# -*- coding: utf-8 -*-
import rospy
from learn_server.srv import Pokemon,PokemonResponse
def Callback(req):
rospy.loginfo("Pokemon: name:%s type:%s gender:%d", req.name, req.type, req.gender)
return PokemonResponse("Pokemon response. Done")
def pokemon_server():
rospy.init_node('poekmon_server_py')
# 创建一个名为/pokemon_show的server,注册回调函数Callback
s = rospy.Service('/pokemon_show', Pokemon, Callback)
# 循环等待回调函数
print "Ready to show pokemon information."
rospy.spin()
if __name__ == "__main__":
pokemon_server()
2、客户端实现
# -*- coding: utf-8 -*-
import sys
import rospy
from learn_server.srv import Pokemon, PokemonRequest
def pokemon_client():
rospy.init_node('poekmon_client_py')
# 发现/pokemon_show服务后,创建一个服务客户端,连接名为/pokemon_show的service
rospy.wait_for_service('/pokemon_show')
try:
poekmon_client_py = rospy.ServiceProxy('/pokemon_show', Pokemon)
# 请求服务调用,输入请求数据
response = poekmon_client_py("Psyduck", "water", PokemonRequest.male)
return response.result
except rospy.ServiceException, e:
print "Service call failed: %s"%e
if __name__ == "__main__":
print "Show person result : %s" %(pokemon_client())