[ROS] [笔记(1)] 一个最简单的例子:Hello Robot(消息、发布者与订阅者)
本例程包含如下内容:
1)创建编译 Package;
2)自定义消息;
3)发布者与订阅者。
0、Hello Robot 的场景:
我们想要完成这样一个场景:
1)有一系列 robot 排成一排(publisher)向管理员(subscriber)报道,每个人都发一个消息(robotID),包含 name 和 id 类似:
name=robot id=0
name=robot id=1
name=robot id=2
2)有一个管理员订阅了这个消息(robotID),然后读取消息内容并且和每个机器人打招呼:
hello robot 0
hello robot 1
hello robot 2
要完成以上的功能,我们需要创建消息(robotID)、发送消息的发送者(publisher)、接收消息的订阅者(subscriber)。他们之间的关系是这样的:
1、创建 ros 目录:
先我们为所有的 ROS 工程创建如下路径:
1 | mkdir ~/ROS |
以后的笔记里面,我们把这一路径称作 ROS_PATH,这一路径就是我们所有 ros 工程的基本路径。
2、创建 workspace 和 package:
一个典型的 ros 工程是在一个 workspace 下包含若干个包,每一个包应该完成一套独立的功能。它的路径通常类似于:
workspace_folder/ -- WORKSPACE
src/ -1- SOURCE SPACE
CMakeLists.txt -- 'Toplevel' CMake file, provided by catkin
package_1/
CMakeLists.txt -- CMakeLists.txt file for package_1
package.xml -- Package manifest for package_1
...
package_n/
CMakeLists.txt -- CMakeLists.txt file for package_n
package.xml -- Package manifest for package_n
我们的 workspace 命名为 hellorobot_ws,我们将所有有关这一工程的包都放在 hellorobot_ws/src 路径下,现在进入 ROS_PATH 创建这个目录:
1) 创建 workspace:
1 2 | mkdir -p hellorobot_ws/src/ cd hellorobot_ws/src |
2)创建 package:
我们在该 workspace 的 src 目录下创建一个名为 hellorobot 的 package:
1 | catkin_create_pkg hellorobot std_msgs rospy roscpp |
这里面 std_msgs rospy roscpp 是我们通常一个最基本的C++包之中需要的依赖项。后面这些依赖项均可以通过配置 package.xml 进行更改。
3)编译 package:
即使什么都不写我们已经可以编译这个包了。编译包需要在 workspace 路径下
1 2 | cd .. catkin_make |
编译成功后在 ROS_PTAH/hellorobot_ws 下就可以看到如下目录结构已经生成了:
build
devel
src
顺便说一下大家在网上下git代码,其实都是其中一个包的src的部分,相当于我们的 ROS_PTAH/hellorobot_ws/src/hellorobot/src,因此只要放入这一目录再按照此步骤运行 catkin_make 即可。
3、创建自定义消息:
1)创建 robotMsg.msg 文件:
在这里我们需要一个消息,包含 name 和 id 两个字段,其中 name 自然都是 robot。我们在 ROS_PTAH/hellorobot_ws/src/hellorobot 路径下创建 msg 文件夹,然后新建 robotMsg.msg 文件:
1 2 3 | mkdir msg cd msg vi robotMsg.msg |
文件内容如下:
1 2 3 | Header header string name int32 id |
2)在 package.xml 添加 message 依赖:
在 package.xml 中找到如下两行代码并且取消注释:
1 2 | <build_depend>message_generation</build_depend> <run_depend>message_runtime</run_depend> |
这两行分别表示在编译和运行时的 message 依赖。
3)在 CMakeList.txt 添加编译依赖:
找到 find_package 添加 message_generation,结果如下:
1 2 3 4 5 6 | find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation ) |
找到 add_message_files ,去掉注释并添加 robotMsg.msg 消息文件:
1 2 3 4 5 6 | ## Generate messages in the 'msg' folder add_message_files( FILES robotMsg.msg # Message2.msg ) |
找到 generate_messages 函数去掉注释,结果如下:
1 2 3 4 5 | ## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES std_msgs ) |
找到 catkin_package 添加如下行并启用该部分,结果如下:
1 2 3 4 5 6 7 | catkin_package( # INCLUDE_DIRS include # LIBRARIES hellorobot # CATKIN_DEPENDS roscpp rospy std_msgs CATKIN_DEPENDS message_runtime # DEPENDS system_lib ) |
顺便说下,如果你运行 catkin_make 以后,这个消息的头文件生成在:
devel/include/hellorobot/robotMsg.h
目录下。
4、创建发布者 publisher:
我们在 ROS_PTAH/hellorobot_ws/src/hellorobot/src 目录下创建 publisher.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 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 | #include "ros/ros.h" //#include "std_msgs/String.h" #include "hellorobot/robotMsg.h" #include <sstream> /** * This tutorial demonstrates simple sending of messages over the ROS system. */ int main(int argc, char **argv) { /** * The ros::init() function needs to see argc and argv so that it can perform * any ROS arguments and name remapping that were provided at the command line. * For programmatic remappings you can use a different version of init() which takes * remappings directly, but for most command-line programs, passing argc and argv is * the easiest way to do it. The third argument to init() is the name of the node. * * You must call one of the versions of ros::init() before using any other * part of the ROS system. */ ros::init(argc, argv, "publisher"); /** * NodeHandle is the main access point to communications with the ROS system. * The first NodeHandle constructed will fully initialize this node, and the last * NodeHandle destructed will close down the node. */ ros::NodeHandle n; /** * The advertise() function is how you tell ROS that you want to * publish on a given topic name. This invokes a call to the ROS * master node, which keeps a registry of who is publishing and who * is subscribing. After this advertise() call is made, the master * node will notify anyone who is trying to subscribe to this topic name, * and they will in turn negotiate a peer-to-peer connection with this * node. advertise() returns a Publisher object which allows you to * publish messages on that topic through a call to publish(). Once * all copies of the returned Publisher object are destroyed, the topic * will be automatically unadvertised. * * The second parameter to advertise() is the size of the message queue * used for publishing messages. If messages are published more quickly * than we can send them, the number here specifies how many messages to * buffer up before throwing some away. */ ros::Publisher chatter_pub = n.advertise<hellorobot::robotMsg>("robotID", 1000); ros::Rate loop_rate(10); /** * A count of how many messages we have sent. This is used to create * a unique string for each message. */ int32_t count = 0; while (ros::ok()) { /** * This is a message object. You stuff it with data, and then publish it. */ //std_msgs::String msg; hellorobot::robotMsg msg; msg.header.stamp = ros::Time::now(); msg.header.frame_id = "/robot"; msg.id = count; msg.name = "Robot"; //std::stringstream ss; //ss << "hello world " << count; //msg.data = ss.str(); ROS_INFO("I am %s %d", msg.name.c_str(), msg.id); /** * The publish() function is how you send messages. The parameter * is the message object. The type of this object must agree with the type * given as a template parameter to the advertise<>() call, as was done * in the constructor above. */ chatter_pub.publish(msg); ros::spinOnce(); loop_rate.sleep(); ++count; } return 0; } |
其中最关键的其实只有几行:
1 | ros::init(argc, argv, "publisher"); |
这一行声明了我们的 Node 名字叫 “publisher”。
1 2 | ros::NodeHandle n; ros::Publisher chatter_pub = n.advertise<hellorobot::robotMsg>("robotID", 1000); |
这一行创建了一个 Node 句柄和 Publisher,它发布的消息是 “robotID”,后面的1000是缓存消息队列长度。
后面是一个循环来不断发送消息,其中:
1 2 3 4 5 | hellorobot::robotMsg msg; msg.header.stamp = ros::Time::now(); msg.header.frame_id = "/robot"; msg.id = count; msg.name = "Robot"; |
这一部分是我们填写的消息内容,主要的后面两行,这是我们设计的消息部分。前面 header 基本上每个消息都会填写一下。
最后我们只需要:
1 | chatter_pub.publish(msg); |
就把消息发送出去了。
1 | ros::spinOnce(); |
这一行也很关键,这是为了让后面 subscriber 的 callback 能够生效。
其余部分是控制循环时间的机制,这里就不赘述了。
5、创建订阅者 subscriber:
我们在 ROS_PTAH/hellorobot_ws/src/hellorobot/src 目录下创建 subscriber.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 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 | #include "ros/ros.h" //#include "std_msgs/String.h" #include "hellorobot/robotMsg.h" //#include "hellorobot/checkRobotSrv.h" /** * This tutorial demonstrates simple receipt of messages over the ROS system. */ void checkRobotCallback(const hellorobot::robotMsg::ConstPtr& msg) { ROS_INFO("Hello %s %d !", msg->name.c_str(), msg->id); } int main(int argc, char **argv) { /** * The ros::init() function needs to see argc and argv so that it can perform * any ROS arguments and name remapping that were provided at the command line. * For programmatic remappings you can use a different version of init() which takes * remappings directly, but for most command-line programs, passing argc and argv is * the easiest way to do it. The third argument to init() is the name of the node. * * You must call one of the versions of ros::init() before using any other * part of the ROS system. */ ros::init(argc, argv, "subscriber"); /** * NodeHandle is the main access point to communications with the ROS system. * The first NodeHandle constructed will fully initialize this node, and the last * NodeHandle destructed will close down the node. */ ros::NodeHandle n; /** * The subscribe() call is how you tell ROS that you want to receive messages * on a given topic. This invokes a call to the ROS * master node, which keeps a registry of who is publishing and who * is subscribing. Messages are passed to a callback function, here * called chatterCallback. subscribe() returns a Subscriber object that you * must hold on to until you want to unsubscribe. When all copies of the Subscriber * object go out of scope, this callback will automatically be unsubscribed from * this topic. * * The second parameter to the subscribe() function is the size of the message * queue. If messages are arriving faster than they are being processed, this * is the number of messages that will be buffered up before beginning to throw * away the oldest ones. */ ros::Subscriber sub = n.subscribe("robotID", 1000, checkRobotCallback); /** * ros::spin() will enter a loop, pumping callbacks. With this version, all * callbacks will be called from within this thread (the main one). ros::spin() * will exit when Ctrl-C is pressed, or the node is shutdown by the master. */ ros::spin(); return 0; } |
其中最关键的其实只有几行:
1 2 3 4 | void checkRobotCallback(const hellorobot::robotMsg::ConstPtr& msg) { ROS_INFO("Hello %s %d !", msg->name.c_str(), msg->id); } |
这是我们真正的回调函数,是 subscriber 接收到订阅消息的处理函数。这里我们仅仅是打出 msg 中我们之前定义的内容,id 和 name。
1 | ros::Subscriber sub = n.subscribe("robotID", 1000, checkRobotCallback); |
这一行与之前 Publisher 类似,唯一不同的是,这里用 checkRobotCallback 指定了我们之前定义的回调函数。
1 | ros::spin(); |
这一行与之前我们使用的 spinOnce 区别是,这里会进入一个循环,不停保持对 callback 的处理,因为我们这里是需要保持一直接收消息的,所以这里用 spin。
其余地方和之前介绍的 Publisher 内容一样。
6、编译:
1)修改 CMakeList.txt 添加 Publisher 和 Subscriber 编译项:
在 CMakeList.txt 文件结尾添加如下几行:
1 2 3 4 5 6 7 | add_executable(publisher src/publisher.cpp) target_link_libraries(publisher ${catkin_LIBRARIES}) add_dependencies(publisher hellorobot_generate_messages_cpp) add_executable(subscriber src/subscriber.cpp) target_link_libraries(subscriber ${catkin_LIBRARIES}) add_dependencies(subscriber hellorobot_generate_messages_cpp) |
2)运行编译命令:
在 ROS_PTAH/hellorobot_ws/ 目录下运行 catkin 编译:
1 | catkin_make |
如果没有问题整个工程就编译完成了。
7、运行测试:
1)首先运行 roscore:
1 | roscore |
2)其次进入 workspace 目录配置环境:
1 2 | cd ROS_PTAH/hellorobot_ws source ./devel/setup.bash |
3)运行 Publisher :
1 | rosrun hellorobot publisher |
将会看到类似输出:
1 2 3 4 5 6 7 8 9 10 11 | [ INFO] [1446532006.457619893]: I am robot 0 [ INFO] [1446532006.557689394]: I am Robot 1 [ INFO] [1446532006.657711920]: I am Robot 2 [ INFO] [1446532006.757726970]: I am Robot 3 [ INFO] [1446532006.857756858]: I am Robot 4 [ INFO] [1446532006.957763088]: I am Robot 5 [ INFO] [1446532007.057815003]: I am Robot 6 [ INFO] [1446532007.157740061]: I am Robot 7 [ INFO] [1446532007.257738466]: I am Robot 8 [ INFO] [1446532007.357759558]: I am Robot 9 [ INFO] [1446532007.457753663]: I am Robot 10 |
4)新开一个 Terminal (Ctrl+Alt+T)运行 subscriber:
首先重复步骤2)配置环境。然后运行:
1 | rosrun hellorobot publisher |
将会看到类似输出:
1 2 3 4 5 6 7 8 9 10 11 | [ INFO] [1446532895.196584845]: Hello robot 0 ! [ INFO] [1446532895.296483439]: Hello Robot 1 ! [ INFO] [1446532895.396375843]: Hello Robot 2 ! [ INFO] [1446532895.196584845]: Hello Robot 3 ! [ INFO] [1446532895.296483439]: Hello Robot 4 ! [ INFO] [1446532895.396375843]: Hello Robot 5 ! [ INFO] [1446532895.496400751]: Hello Robot 6 ! [ INFO] [1446532895.596415008]: Hello Robot 7 ! [ INFO] [1446532895.696396977]: Hello Robot 8 ! [ INFO] [1446532895.796442641]: Hello Robot 9 ! [ INFO] [1446532895.896396418]: Hello Robot 10 ! |
* 但实际上先打开 subscriber 再打开 publisher ,我这里会看到 subscriber 是从 3 开始的,这个还不清楚是什么原因会漏掉前3个消息。
错误提示:
1、错误:Failed to contact master
如果看到如下错误:
[ERROR] [1446531999.044935824]: [registerPublisher] Failed to contact master at [localhost:11311]. Retrying...
请检查 roscore 是否正常打开。
源码下载:
hellorobot.tar
参考文献:
[1] http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29
按照文章一步一步执行,最后编译时出现如下报错,无法完成最后一次编译
-- +++ processing catkin package: 'hellorobot'
-- ==> add_subdirectory(hellorobot)
-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
-- hellorobot: 1 messages, 0 services
-- Configuring done
CMake Error at hellorobot/CMakeLists.txt:211 (add_executable):
Cannot find source file:
Tried extensions .c .C .c++ .cc .cpp .cxx .m .M .mm .h .hh .h++ .hm .hpp
.hxx .in .txx
CMake Error: CMake can not determine linker language for target: publisher
CMake Error: Cannot determine link language for target "publisher".
-- Generating done
-- Build files have been written to: /home/yzy/ROS/hellorobot_ws/build
Makefile:724: recipe for target 'cmake_check_build_system' failed
make: *** [cmake_check_build_system] Error 1
Invoking "make cmake_check_build_system" failed
yzy@yzy-virtual-machine:~/ROS/hellorobot_ws$