使用自定义的消息类型,实现service方式的节点间双向通信
在package目录下创建msg和srv目录,存放package需要使用的.msg和.srv文件.
在ROS中,message被设计为一种称为"language-neutral interface definition language (IDL)"的接口型定义语言.例如描述点云的消息类型通常被定义为:
Header header // 包含ROS中常用的时间戳和坐标系信息
Point32[] pts
ChannelFloat32[] chan
消息类型类似与C语言中的结构体,但是对于具体的ROS实现语言如C++或者Python,这种消息类型是无法兼容的,因此需要使用message_generation根据具体实现语言转换为C++或者Python源代码.
定义完.msg文件后需要修改Package.xml,编译时使用message_generation生成消息类型对应目标语言的源代码,运行时,需要依赖message_runtime
<build_depend>message_generation</build_depend>
<run_depend>message_runtime</run_depend>
并且修改CMakeLists.txt
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
catkin_package(
...
CATKIN_DEPENDS message_runtime ...
...)
add_message_files(
FILES
***.msg
)
generate_messages(
DEPENDENCIES
std_msgs
)
1. 在依赖的catkin组件中添加message_generation.以及动态链接的message_runtime;
2. 添加*.msg文件,要和msg目录下的.msg文件对应;
3. 最后,需要确保一个generate_messages()函数被调用,用于生成自定义msg的C++或者Python源文件,如果自定义的msg中使用了std_msgs类型,例如int64, Header等等,还需要添加依赖,一般std_msgs是必须的,这里还可以添加别的依赖消息类型.
这里需要注意,定义.srv文件完成后和定义.msg文件完成后需要做的事情完全一样,因为.srv文件也是通过message_generation来生成对应的C++/Python/Lisp/Octave源文件的.
生成的.msg和.srv文件(C++或者Python,Lisp,Octave实现)在catkin(而不是package目录)的devel目录下.因此如果其他package使用当前package中定义的消息类型,实际包含的是该文件.唯一的区别就是在CMakeLists.txt中需要加入.srv文件:
add_service_files(
FILES
***.srv
)
一般来说,习惯是"A good ROS practice is to collect related messages, services and actions into a separate package with no other API. That simplifies the package dependency graph."在另外一个独立的package中,将所有需要的messages, services,以及actions都定义好,该package不提供别的功能,这样package的依赖关系比较容易处理.注意,使用别的package的这些类型,需要再修改Package.xml添加包依赖:
<build_depend>name_of_package_containing_custom_msg</build_depend>
<run_depend>name_of_package_containing_custom_msg</run_depend>
最后我们使用C++在package的src目录下实现一个service通信的服务器端server.cpp和client.cpp
server.cpp:
//
// Created by shang on 4/11/17.
// #include "ros/ros.h"
// in ~/catkin_ws/devel/include for C++
#include "my_service_test/my_srv.h" bool judge(my_service_test::my_srv::Request& req, my_service_test::my_srv::Response& res)
{
if(req.req%) res.res = ;
else res.res = ;
ROS_INFO("request:x=%ld", (long int)req.req);
ROS_INFO("sending back response:[%ld]",(long int)res.res);
return true;
} int main(int argc, char** argv)
{
ros::init(argc, argv, "odev_server");
ros::NodeHandle n;
ros::ServiceServer service = n.advertiseService("odev_service",judge);
ROS_INFO("Ready to judge.");
ros::spin();
return ;
}
client.cpp:
//
// Created by shang on 4/11/17.
// #include "ros/ros.h"
#include "my_service_test/my_srv.h"
#include <cstdlib> int main(int argc, char** argv){
ros::init(argc, argv, "odev_client");
ros::NodeHandle n;
ros::ServiceClient client = n.serviceClient<my_service_test::my_srv>("odev_service");
my_service_test::my_srv srv;
srv.request.req = atoll(argv[]);
if(client.call(srv)){
if(srv.response.res)
ROS_INFO("odd or even: odd");
else
ROS_INFO("odd or even: even");
}
else{
ROS_ERROR("Failed to judge!");
return ;
}
return ;
}
修改CMakeLists.txt配置这两个文件的编译过程:
# for "ros/ros.h"
include_directories(
# opt/ros/indigo/include
${catkin_INCLUDE_DIRS}
) add_executable(odev_server src/odev_server.cpp)
target_link_libraries(odev_server ${catkin_LIBRARIES})
add_dependencies(odev_server my_service_test_gencpp) add_executable(odev_client src/odev_client.cpp)
target_link_libraries(odev_client ${catkin_LIBRARIES})
add_dependencies(odev_client my_service_test_gencpp)
catkin_make后
运行
roscore
rosrun my_service_test odev_server
rosrun my_service_test odev_client 3
并且注意,其实service并不一定需要使用自定义的msg,因此在该程序的CMakeLists.txt中,不需要add_message_files()