Note: This tutorial assumes that you have completed the previous tutorials: ROS tutorials, Using CvBridge to Convert Between ROS Images and OpenCV Images.
(!) 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 Image Publisher (C++)

Description: This tutorial shows how to publish images using all available transports.

Tutorial Level: BEGINNER

Next Tutorial: Writing a Simple Image Subscriber

Writing a Simple Image Publisher

Here we'll create the publisher node which will continually publish an image.

Change to the directory you've created for these tutorials:

$ roscd image_transport_tutorial

(Assuming you have created your package in ~/image_transport_ws)

$ cd ~/image_transport_ws/
$ git clone https://github.com/ros-perception/image_common.git
$ mkdir src
$ ln -s `pwd`/image_common/image_transport/tutorial/ ./src/image_transport_tutorial

The Code

First, create `src/my_publisher.cpp` in package `image_transport_tutorial` with your favorite editor, and place the following inside it:

Have a look at my_publisher.cpp:

   1 #include <ros/ros.h>
   2 #include <image_transport/image_transport.h>
   3 #include <opencv2/highgui/highgui.hpp>
   4 #include <cv_bridge/cv_bridge.h>
   5 
   6 int main(int argc, char** argv)
   7 {
   8   ros::init(argc, argv, "image_publisher");
   9   ros::NodeHandle nh;
  10   image_transport::ImageTransport it(nh);
  11   image_transport::Publisher pub = it.advertise("camera/image", 1);
  12   cv::Mat image = cv::imread(argv[1], CV_LOAD_IMAGE_COLOR);
  13   cv::waitKey(30);
  14   sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
  15 
  16   ros::Rate loop_rate(5);
  17   while (nh.ok()) {
  18     pub.publish(msg);
  19     ros::spinOnce();
  20     loop_rate.sleep();
  21   }
  22 }

The Code Explained

Now, let's break down the code piece by piece. For lines not explained here, review Writing a Simple Publisher and Subscriber (C++).

Error: No code_block found image_transport/image_transport.h includes everything we need to publish and subscribe to images.

Error: No code_block found These headers will allow us to load an image using OpenCV and convert it to the ROS message format.

Error: No code_block found We create an ImageTransport instance, initializing it with our NodeHandle. We use methods of ImageTransport to create image publishers and subscribers, much as we use methods of NodeHandle to create generic ROS publishers and subscribers.

Error: No code_block found Advertise that we are going to be publishing images on the base topic "camera/image". Depending on whether more plugins are built, additional (per-plugin) topics derived from the base topic may also be advertised. The second argument is the size of our publishing queue.

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

Error: No code_block found We load a user-specified (on the command line) color image from disk using OpenCV, then convert it to the ROS type sensor_msgs/Image. See this tutorial for more on ROS-OpenCV image conversion.

Error: No code_block found We broadcast the image to anyone connected to one of our topics, exactly as we would have using a ros::Publisher.

Adding video stream from a webcam

The example above requires a path of an image file to be added as a command line parameter (cv::imread(argv[1], CV_LOAD_IMAGE_COLOR)). This image will be converted and send as a message to an image subscriber. In most cases however this is not a very practical example since often you are required to handle streaming data (for example: multiple webcameras mounted on a robot record the scene around it and you have to pass the image date to some other node for further analysis). You can modify the example quite easily to make it work with a video device supported by cv::VideoCapture (in case it is not you have to handle it accordingly):

   1 #include <ros/ros.h>
   2 #include <image_transport/image_transport.h>
   3 #include <opencv2/highgui/highgui.hpp>
   4 #include <cv_bridge/cv_bridge.h>
   5 #include <sstream> // for converting the command line parameter to integer
   6 
   7 int main(int argc, char** argv)
   8 {
   9   // Check if video source has been passed as a parameter
  10   if(argv[1] == NULL) return 1;
  11 
  12   ros::init(argc, argv, "image_publisher");
  13   ros::NodeHandle nh;
  14   image_transport::ImageTransport it(nh);
  15   image_transport::Publisher pub = it.advertise("camera/image", 1);
  16 
  17   // Convert the passed as command line parameter index for the video device to an integer
  18   std::istringstream video_sourceCmd(argv[1]);
  19   int video_source;
  20   // Check if it is indeed a number
  21   if(!(video_sourceCmd >> video_source)) return 1;
  22 
  23   cv::VideoCapture cap(video_source);
  24   // Check if video device can be opened with the given index
  25   if(!cap.isOpened()) return 1;
  26   cv::Mat frame;
  27   sensor_msgs::ImagePtr msg;
  28 
  29   ros::Rate loop_rate(5);
  30   while (nh.ok()) {
  31     cap >> frame;
  32     // Check if grabbed frame is actually full with some content
  33     if(!frame.empty()) {
  34       msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg();
  35       pub.publish(msg);
  36       cv::waitKey(1);
  37     }
  38 
  39     ros::spinOnce();
  40     loop_rate.sleep();
  41   }
  42 }

If you have a single device you do not need to do the whole routine with passing a command line argument (argv[1]) and parsing it at all. In this case you can hard-code the index/address of the device and directly pass it to the video capturing structure in OpenCV (example: cv::VideoCapture(0) if /dev/video0 is used). In addition multiple checks are also included here to make sure that the publisher does not brake if in case the camera is shut downs or similar issue). If the retrieved frame from the video device is not empty it will be then converted to a ROS message, which will be published by the publisher.

Building your node

Add the following line to your CMakeLists.txt file:

rosbuild_add_executable(my_publisher src/my_publisher.cpp)

and do

$ make

Just run:

catkin_make

Now let's write a simple image subscriber.

Wiki: image_transport/Tutorials/PublishingImages (last edited 2015-05-24 18:51:48 by Diego Alejandro Gomez)