使用自定義的消息類型,實現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%2) res.res = 1; else res.res = 0; 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 0; }
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[1]); 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 1; } return 0; }
修改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()