Note: This tutorial assumes that you have completed the previous tutorials: installing ROS.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Writing a Simple Publisher and Subscriber (C++) (plain cmake)

Description: This tutorial covers how to write a publisher and subscriber node in C++ using plain cmake (i.e., not catkin).

Tutorial Level: BEGINNER

Note: Be sure that you have already installed ROS and remember that you must source the appropriate setup file in every shell you create.

Making a directory in which to work

To help keep yourself organized, make a directory in which to work. You can use any name; we'll just call it pubsub:

mkdir -p pubsub
cd pubsub

Writing the Publisher Node

"Node" is the ROS term for an executable that is connected to the ROS network. Here we'll create a publisher ("talker") node which will continually broadcast a message.

The Code

Create a file named talker.cpp within the pubsub directory and paste the following inside it:

https://raw.github.com/ros/ros_tutorials/kinetic-devel/roscpp_tutorials/talker/talker.cpp

  27 #include "ros/ros.h"
  28 #include "std_msgs/String.h"
  29 
  30 #include <sstream>
  31 
  32 /**
  33  * This tutorial demonstrates simple sending of messages over the ROS system.
  34  */
  35 int main(int argc, char **argv)
  36 {
  37   /**
  38    * The ros::init() function needs to see argc and argv so that it can perform
  39    * any ROS arguments and name remapping that were provided at the command line.
  40    * For programmatic remappings you can use a different version of init() which takes
  41    * remappings directly, but for most command-line programs, passing argc and argv is
  42    * the easiest way to do it.  The third argument to init() is the name of the node.
  43    *
  44    * You must call one of the versions of ros::init() before using any other
  45    * part of the ROS system.
  46    */
  47   ros::init(argc, argv, "talker");
  48 
  49   /**
  50    * NodeHandle is the main access point to communications with the ROS system.
  51    * The first NodeHandle constructed will fully initialize this node, and the last
  52    * NodeHandle destructed will close down the node.
  53    */
  54   ros::NodeHandle n;
  55 
  56   /**
  57    * The advertise() function is how you tell ROS that you want to
  58    * publish on a given topic name. This invokes a call to the ROS
  59    * master node, which keeps a registry of who is publishing and who
  60    * is subscribing. After this advertise() call is made, the master
  61    * node will notify anyone who is trying to subscribe to this topic name,
  62    * and they will in turn negotiate a peer-to-peer connection with this
  63    * node.  advertise() returns a Publisher object which allows you to
  64    * publish messages on that topic through a call to publish().  Once
  65    * all copies of the returned Publisher object are destroyed, the topic
  66    * will be automatically unadvertised.
  67    *
  68    * The second parameter to advertise() is the size of the message queue
  69    * used for publishing messages.  If messages are published more quickly
  70    * than we can send them, the number here specifies how many messages to
  71    * buffer up before throwing some away.
  72    */
  73   ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
  74 
  75   ros::Rate loop_rate(10);
  76 
  77   /**
  78    * A count of how many messages we have sent. This is used to create
  79    * a unique string for each message.
  80    */
  81   int count = 0;
  82   while (ros::ok())
  83   {
  84     /**
  85      * This is a message object. You stuff it with data, and then publish it.
  86      */
  87     std_msgs::String msg;
  88 
  89     std::stringstream ss;
  90     ss << "hello world " << count;
  91     msg.data = ss.str();
  92 
  93     ROS_INFO("%s", msg.data.c_str());
  94 
  95     /**
  96      * The publish() function is how you send messages. The parameter
  97      * is the message object. The type of this object must agree with the type
  98      * given as a template parameter to the advertise<>() call, as was done
  99      * in the constructor above.
 100      */
 101     chatter_pub.publish(msg);
 102 
 103     ros::spinOnce();
 104 
 105     loop_rate.sleep();
 106     ++count;
 107   }
 108 
 109 
 110   return 0;
 111 }

The Code Explained

Now, let's break the code down.

  27 #include "ros/ros.h"
  28 

ros/ros.h is a convenience include that includes all the headers necessary to use the most common public pieces of the ROS system.

  28 #include "std_msgs/String.h"
  29 

This includes the std_msgs/String message, which resides in the std_msgs package. This is a header generated automatically from the String.msg file in that package. For more information on message definitions, see the msg page.

  47   ros::init(argc, argv, "talker");

Initialize ROS. This allows ROS to do name remapping through the command line -- not important for now. This is also where we specify the name of our node. Node names must be unique in a running system.

The name used here must be a base name, ie. it cannot have a / in it.

  54   ros::NodeHandle n;

Create a handle to this process' node. The first NodeHandle created will actually do the initialization of the node, and the last one destructed will cleanup any resources the node was using.

  73   ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);

Tell the master that we are going to be publishing a message of type std_msgs/String on the topic chatter. This lets the master tell any nodes listening on chatter that we are going to publish data on that topic. The second argument is the size of our publishing queue. In this case if we are publishing too quickly it will buffer up a maximum of 1000 messages before beginning to throw away old ones.

NodeHandle::advertise() returns a ros::Publisher object, which serves two purposes: 1) it contains a publish() method that lets you publish messages onto the topic it was created with, and 2) when it goes out of scope, it will automatically unadvertise.

  75   ros::Rate loop_rate(10);

A ros::Rate object allows you to specify a frequency that you would like to loop at. It will keep track of how long it has been since the last call to Rate::sleep(), and sleep for the correct amount of time.

In this case we tell it we want to run at 10Hz.

  81   int count = 0;
  82   while (ros::ok())
  83   {

By default roscpp will install a SIGINT handler which provides Ctrl-C handling which will cause ros::ok() to return false if that happens.

ros::ok() will return false if:

  • a SIGINT is received (Ctrl-C)
  • we have been kicked off the network by another node with the same name
  • ros::shutdown() has been called by another part of the application.

  • all ros::NodeHandles have been destroyed

Once ros::ok() returns false, all ROS calls will fail.

  87     std_msgs::String msg;
  88 
  89     std::stringstream ss;
  90     ss << "hello world " << count;
  91     msg.data = ss.str();

We broadcast a message on ROS using a message-adapted class, generally generated from a msg file. More complicated datatypes are possible, but for now we're going to use the standard String message, which has one member: "data".

 101     chatter_pub.publish(msg);

Now we actually broadcast the message to anyone who is connected.

  93     ROS_INFO("%s", msg.data.c_str());

ROS_INFO and friends are our replacement for printf/cout. See the rosconsole documentation for more information.

 103     ros::spinOnce();

Calling ros::spinOnce() here is not necessary for this simple program, because we are not receiving any callbacks. However, if you were to add a subscription into this application, and did not have ros::spinOnce() here, your callbacks would never get called. So, add it for good measure.

 105     loop_rate.sleep();

Now we use the ros::Rate object to sleep for the time remaining to let us hit our 10Hz publish rate.

Here's the condensed version of what's going on:

  • Initialize the ROS system
  • Advertise that we are going to be publishing std_msgs/String messages on the chatter topic to the master

  • Loop while publishing messages to chatter 10 times a second

Now we need to write a node to receive the messsages.

Writing the Subscriber Node

The Code

Create a file named listener.cpp within the pubsub directory and paste the following inside it:

https://raw.github.com/ros/ros_tutorials/kinetic-devel/roscpp_tutorials/listener/listener.cpp

  28 #include "ros/ros.h"
  29 #include "std_msgs/String.h"
  30 
  31 /**
  32  * This tutorial demonstrates simple receipt of messages over the ROS system.
  33  */
  34 void chatterCallback(const std_msgs::String::ConstPtr& msg)
  35 {
  36   ROS_INFO("I heard: [%s]", msg->data.c_str());
  37 }
  38 
  39 int main(int argc, char **argv)
  40 {
  41   /**
  42    * The ros::init() function needs to see argc and argv so that it can perform
  43    * any ROS arguments and name remapping that were provided at the command line.
  44    * For programmatic remappings you can use a different version of init() which takes
  45    * remappings directly, but for most command-line programs, passing argc and argv is
  46    * the easiest way to do it.  The third argument to init() is the name of the node.
  47    *
  48    * You must call one of the versions of ros::init() before using any other
  49    * part of the ROS system.
  50    */
  51   ros::init(argc, argv, "listener");
  52 
  53   /**
  54    * NodeHandle is the main access point to communications with the ROS system.
  55    * The first NodeHandle constructed will fully initialize this node, and the last
  56    * NodeHandle destructed will close down the node.
  57    */
  58   ros::NodeHandle n;
  59 
  60   /**
  61    * The subscribe() call is how you tell ROS that you want to receive messages
  62    * on a given topic.  This invokes a call to the ROS
  63    * master node, which keeps a registry of who is publishing and who
  64    * is subscribing.  Messages are passed to a callback function, here
  65    * called chatterCallback.  subscribe() returns a Subscriber object that you
  66    * must hold on to until you want to unsubscribe.  When all copies of the Subscriber
  67    * object go out of scope, this callback will automatically be unsubscribed from
  68    * this topic.
  69    *
  70    * The second parameter to the subscribe() function is the size of the message
  71    * queue.  If messages are arriving faster than they are being processed, this
  72    * is the number of messages that will be buffered up before beginning to throw
  73    * away the oldest ones.
  74    */
  75   ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
  76 
  77   /**
  78    * ros::spin() will enter a loop, pumping callbacks.  With this version, all
  79    * callbacks will be called from within this thread (the main one).  ros::spin()
  80    * will exit when Ctrl-C is pressed, or the node is shutdown by the master.
  81    */
  82   ros::spin();
  83 
  84   return 0;
  85 }

The Code Explained

Now, let's break it down piece by piece, ignoring some pieces that have already been explained above.

  34 void chatterCallback(const std_msgs::String::ConstPtr& msg)
  35 {
  36   ROS_INFO("I heard: [%s]", msg->data.c_str());
  37 }

This is the callback function that will get called when a new message has arrived on the chatter topic. The message is passed in a boost shared_ptr, which means you can store it off if you want, without worrying about it getting deleted underneath you, and without copying the underlying data.

  75   ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);

Subscribe to the chatter topic with the master. ROS will call the chatterCallback() function whenever a new message arrives. The 2nd argument is the queue size, in case we are not able to process messages fast enough. In this case, if the queue reaches 1000 messages, we will start throwing away old messages as new ones arrive.

NodeHandle::subscribe() returns a ros::Subscriber object, that you must hold on to until you want to unsubscribe. When the Subscriber object is destructed, it will automatically unsubscribe from the chatter topic.

There are versions of the NodeHandle::subscribe() function which allow you to specify a class member function, or even anything callable by a Boost.Function object. The roscpp overview contains more information.

  82   ros::spin();

ros::spin() enters a loop, calling message callbacks as fast as possible. Don't worry though, if there's nothing for it to do it won't use much CPU. ros::spin() will exit once ros::ok() returns false, which means ros::shutdown() has been called, either by the default Ctrl-C handler, the master telling us to shutdown, or it being called manually.

There are other ways of pumping callbacks, but we won't worry about those here. The roscpp_tutorials package has some demo applications which demonstrate this. The roscpp overview also contains more information.

Again, here's a condensed version of what's going on:

  • Initialize the ROS system
  • Subscribe to the chatter topic

  • Spin, waiting for messages to arrive
  • When a message arrives, the chatterCallback() function is called

Building your nodes

You need to tell cmake how to build (compile and link) your C++ code. Create a file named CMakeLists.txt in the pubsub directory and paste the following inside it:

https://raw.githubusercontent.com/gerkey/ros1_external_use/master/ros1_comms/CMakeLists.txt

   1 cmake_minimum_required(VERSION 2.8.3)
   2 project(myproject)
   3 
   4 # Build the talker and listener. Each one uses the following ROS packages,
   5 # which we need to find_package() individually:
   6 #   roscpp (the client library)
   7 #   std_msgs (contains the std_msgs/String message type)
   8 find_package(roscpp REQUIRED)
   9 find_package(std_msgs REQUIRED)
  10 # We've found them; now use their variables in the usual way to configure
  11 # the compile and link steps.
  12 # Note: we skip calling link_directories() because ROS packages follow the
  13 # recommended CMake practice of returning absolute paths to libraries
  14 include_directories(${roscpp_INCLUDE_DIRS})
  15 include_directories(${std_msgs_INCLUDE_DIRS})
  16 
  17 add_executable(talker talker.cpp)
  18 target_link_libraries(talker ${roscpp_LIBRARIES} ${std_msgs_LIBRARIES})
  19 
  20 add_executable(listener listener.cpp)
  21 target_link_libraries(listener ${roscpp_LIBRARIES} ${std_msgs_LIBRARIES})
  22 
  23 # (optional) Install the executables.
  24 install(TARGETS talker listener
  25         DESTINATION bin)

Build your nodes in a subdirectory of pubsub named build using the standard cmake sequence:

mkdir -p build
cd build
cmake ..
make

Running the nodes

Running nodes requires you have a ROS core started. Open a new shell, and type:

roscore

If all goes well, you should see an output that looks something like this:

... logging to /u/takayama/.ros/logs/83871c9c-934b-11de-a451-001d927076eb/roslaunch-ads-31831.log
... loading XML file [/wg/stor1a/rosbuild/shared_installation/ros/tools/roslaunch/roscore.xml]
Added core node of type [rosout/rosout] in namespace [/]
started roslaunch server http://ads:54367/

SUMMARY
======

NODES

changing ROS_MASTER_URI to [http://ads:11311/] for starting master locally
starting new master (master configured for auto start)
process[master]: started with pid [31874]
ROS_MASTER_URI=http://ads:11311/
setting /run_id to 83871c9c-934b-11de-a451-001d927076eb
+PARAM [/run_id] by /roslaunch
+PARAM [/roslaunch/uris/ads:54367] by /roslaunch
process[rosout-1]: started with pid [31889]
started core service [/rosout]
+SUB [/time] /rosout http://ads:33744/
+SERVICE [/rosout/get_loggers] /rosout http://ads:33744/
+SERVICE [/rosout/set_logger_level] /rosout http://ads:33744/
+PUB [/rosout_agg] /rosout http://ads:33744/
+SUB [/rosout] /rosout http://ads:33744/

Now everything is set to run talker/listener. Open a new shell, go to your pubsub directory and type:

./build/talker

Now in the original shell type:

./build/listener

Talker should begin outputting text similar to:

[ INFO] I published [Hello there! This is message [0]]
[ INFO] I published [Hello there! This is message [1]]
[ INFO] I published [Hello there! This is message [2]]
...

And listener should begin outputting text similar to:

[ INFO] Received [Hello there! This is message [20]]
[ INFO] Received [Hello there! This is message [21]]
[ INFO] Received [Hello there! This is message [22]]
...

Congratulations! You've just run your first ROS nodes. For more example code, see the roscpp_tutorials package.

Using roslaunch/rosrun

In order for roslaunch to find launch files associated with this node, you'll need to have a package.xml file located next to a launch folder which contains launch files, and you'll need to make sure that the path to that package.xml file can be found in the environment variable ROS_PACKAGE_PATH. The package.xml file just needs a valid name field, i.e. it can be as simple as

<?xml version="1.0"?>
<package>
  <name>my_pkg_name</name>
</package>

In order for rosrun to be able to detect this executable, you'll need to install your executable into a folder structure that look like this:

  • The root folder contains an empty .catkin file
  • The root folder appears in the CMAKE_PREFIX_PATH environment variable
  • The root folder contains either a libexec or share folder which contains a folder named after the package, which then contains your executable

That last one was a little wordy. Here's what the directory will look like:

/path/to/installation_folder
├── .catkin <- empty file
└── libexec <- could be 'share' instead of 'libexec', both are valid
    └── my_pkg_name
        └── my_executable

And /path/to/installation_folder needs to be appear in CMAKE_PREFIX_PATH. You may find it helpful to create your own setup.sh file to autopopulate the ROS_PACKAGE_PATH and CMAKE_PREFIX_PATH variables.

Wiki: ROS/Tutorials/WritingPublisherSubscriber(c++)(plain cmake) (last edited 2020-01-13 02:33:50 by actinium226)