ROS是基于topic发布和订阅来实现通信,底层是TCP来发送消息,具体原理本文不在详细介绍。本文将手动实现两个ros节点的通信。
首先进入ROS,并进入/catkin_ws/src目录
创建新的package
1 catkin_create_pkg basic_topic roscpp std_msgs
#向功能包添加自定义消息文件(.msg)
1 2 3 roscd custom_msg_topic mkdir msg && cd msg gedit custom_msg.msg
在custom_msg.msg文件中输入如下的内容:
1 2 3 4 string first_name string last_name uint8 age string character
修改CMakeLists.txt文件的内容为:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 cmake_minimum_required(VERSION 2.8.3) project(custom_msg_topic) find_package(catkin REQUIRED COMPONENTS roscpp std_msgs message_generation ) add_message_files( FILES custom_msg.msg ) generate_messages( DEPENDENCIES std_msgs ) catkin_package( LIBRARIES custom_msg_topic CATKIN_DEPENDS roscpp message_runtime ) include_directories( ${catkin_INCLUDE_DIRS} )
回到功能包所在的工作空间,构建功能包:
1 2 cd ~/catkin_ws catkin_make
编译之后会在include文件夹下生成对应的custom_msg.h文件
可以来检测一下
1 2 3 4 5 ros@sunxin-ThinkPad-T480s.master> rosmsg show custom_msg_topic/custom_msg string first_name string last_name uint8 age string character
生成了自定义的消息头文件之后,我们就可以利用自定义的消息格式来编写节点了.
建立publisher节点
一般包含如下要素:
ROS节点初始化
创建节点句柄
穿件publisher
设置循环频率
1 2 roscd custom_msg_topic/src gedit custom_msg_publisher.cpp
并编辑cpp文件加入以下代码(代码具体讲解参考文下参考文献)
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 #include "ros/ros.h" #include "custom_msg_topic/custom_msg.h" #include <sstream> int main (int argc, char **argv) { ros::init(argc, argv, "custom_msg_publisher" ); ros::NodeHandle nh; ros::Publisher custom_msg_pub = nh.advertise<custom_msg_topic::custom_msg>("test" , 100 ); ros::Rate loop_rate (10 ) ; while (ros::ok()) { custom_msg_topic::custom_msg msg; std ::stringstream ss; ss<<"Xiao Xin" ; ss>>msg.last_name; ss>>msg.first_name; msg.age = 18 ; msg.character = "lovely" ; custom_msg_pub.publish(msg); loop_rate.sleep(); } return 0 ; }
#建立subsriber节点
一般包含如下要素:
回调函数
ROS节点初始化
创建节点句柄
穿件publisher
循环等待回调函数
1 2 roscd custom_msg_topic/src gedit custom_msg_subscriber.cpp
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 #include "ros/ros.h" #include "custom_msg_topic/custom_msg.h" void test_infoCallback (const custom_msg_topic::custom_msgConstPtr &msg) { ROS_INFO("I heard: [%s %s]" , msg->last_name.c_str(), msg->first_name.c_str()); ROS_INFO("his age is: [%d]; and he is [%s]" , msg->age, msg->character.c_str()); } int main (int argc, char **argv) { ros::init(argc, argv, "custom_msg_subscriber" ); ros::NodeHandle nh; ros::Subscriber sub = nh.subscribe("test" , 1000 , test_infoCallback); ros::spin(); return 0 ; }
修改功能包的CMakeLists.txt文件
打开终端
1 2 roscd custom_msg_topic gedit CMakeLists.txt
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 cmake_minimum_required(VERSION 2.8.3) project(custom_msg_topic) find_package(catkin REQUIRED COMPONENTS roscpp std_msgs message_generation ) add_message_files( FILES custom_msg.msg ) generate_messages( DEPENDENCIES std_msgs ) catkin_package( LIBRARIES custom_msg_topic CATKIN_DEPENDS roscpp message_runtime ) include_directories( ${catkin_INCLUDE_DIRS} ) # 下面是需要添加的内容 add_executable(custom_msg_publisher src/custom_msg_publisher.cpp) add_executable(custom_msg_subscriber src/custom_msg_subscriber.cpp) add_dependencies(custom_msg_publisher ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) add_dependencies(custom_msg_subscriber ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(custom_msg_publisher ${catkin_LIBRARIES}) target_link_libraries(custom_msg_subscriber ${catkin_LIBRARIES})
运行
然后再次编译一下
1 2 cd ~/catkin_ws catkin_make
开始运行~
1 2 roscore rosrun custom_msg_topic custom_msg_publisher
接着可以查看一些详情
1 2 rosnode info rosrun custom_msg_topic custom_msg_subscriber rostopic hz test
参考文献:
http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber(c++)