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 Subscriber (C++)

Description: This tutorial shows how to subscribe to images using any available transport. By using the image_transport subscriber to subscribe to images, any image transport can be used at run-time. To learn how to actually use a specific image transport, see the next tutorial.

Tutorial Level: BEGINNER

Next Tutorial: Running the Simple Image Publisher and Subscriber with Different Transports

Writing a Simple Image Subscriber

Here we'll create the subscriber node which will display an image topic on screen.

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/src/image_transport_tutorial

The Code

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

Have a look at the src/my_subscriber.cpp file:

   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 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
   7 {
   8   try
   9   {
  10     cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
  11     cv::waitKey(30);
  12   }
  13   catch (cv_bridge::Exception& e)
  14   {
  15     ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
  16   }
  17 }
  18 
  19 int main(int argc, char **argv)
  20 {
  21   ros::init(argc, argv, "image_listener");
  22   ros::NodeHandle nh;
  23   cv::namedWindow("view");
  24 
  25   image_transport::ImageTransport it(nh);
  26   image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);
  27   ros::spin();
  28   cv::destroyWindow("view");
  29 }

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++).

   2 #include <image_transport/image_transport.h>
   3 

image_transport/image_transport.h includes everything we need to publish and subscribe to images.

   3 #include <opencv2/highgui/highgui.hpp>
   4 #include <cv_bridge/cv_bridge.h>
   5 

These headers will allow us to display images using OpenCV's simple GUI capabilities.

   6 void imageCallback(const sensor_msgs::ImageConstPtr& msg)

This is the callback function that will get called when a new image has arrived on the "camera/image" topic. Although the image may have been sent in some arbitrary transport-specific message type, notice that the callback need only handle the normal sensor_msgs/Image type. All image encoding/decoding is handled automagically for you.

   7 {
   8   try
   9   {
  10     cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
  11     cv::waitKey(30);
  12   }
  13   catch (cv_bridge::Exception& e)
  14   {
  15     ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
  16   }

The body of the callback. We convert the ROS image message to an OpenCV image with BGR pixel encoding, then show it in a display window. See this tutorial for more on ROS-OpenCV image conversion.

  22   ros::NodeHandle nh;
  23   cv::namedWindow("view");

Create an OpenCV display window.

  24 

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.

  25   image_transport::ImageTransport it(nh);

Subscribe to the "camera/image" base topic. The actual ROS topic subscribed to depends on which transport is used. In the default case, "raw" transport, the topic is in fact "camera/image" with type sensor_msgs/Image. ROS will call the "imageCallback" function whenever a new image arrives. The 2nd argument is the queue size.

subscribe() returns an image_transport::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 "camera/image" base topic.

There are versions of the subscribe() function which allow you to specify a class member function, or even anything callable by a Boost.Function object.

  27   ros::spin();

Dispose of our display window.

In just a few lines of code, we have written a ROS image viewer that can handle images in both raw and a variety of compressed forms. In fact, this is a stripped-down version of image_view.

Building your node

Add the following line to your CMakeLists.txt file:

rosbuild_add_executable(my_subscriber src/my_subscriber.cpp)

and do

$ make

Just run:

$ catkin_make

Next let's run our publisher and subscriber with different image transports.

Wiki: image_transport/Tutorials/SubscribingToImages (last edited 2021-01-01 14:39:56 by OnurCanYücedağ)