| Note: This tutorial assumes that you have completed the previous tutorials: ROS tutorials, Using CvBridge to Convert Between ROS Images and OpenCV Images. |
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 learning_image_transport
The Code
First, create src/my_publisher.cpp in package learning_image_transport with your favorite editor, and place the following inside it:
1 #include <ros/ros.h>
2 #include <image_transport/image_transport.h>
3 #include <opencv/cvwimage.h>
4 #include <opencv/highgui.h>
5 #include <cv_bridge/CvBridge.h>
6
7 int main(int argc, char** argv)
8 {
9 ros::init(argc, argv, "image_publisher");
10 ros::NodeHandle nh;
11 image_transport::ImageTransport it(nh);
12 image_transport::Publisher pub = it.advertise("camera/image", 1);
13
14 cv::WImageBuffer3_b image( cvLoadImage(argv[1], CV_LOAD_IMAGE_COLOR) );
15 sensor_msgs::ImagePtr msg = sensor_msgs::CvBridge::cvToImgMsg(image.Ipl(), "bgr8");
16
17 ros::Rate loop_rate(5);
18 while (nh.ok()) {
19 pub.publish(msg);
20 ros::spinOnce();
21 loop_rate.sleep();
22 }
23 }
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++).
image_transport/image_transport.h includes everything we need to publish and subscribe to images.
These headers will allow us to load an image using OpenCV and convert it to the ROS message format.
11 image_transport::ImageTransport it(nh);
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.
12 image_transport::Publisher pub = it.advertise("camera/image", 1);
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.
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.
19 pub.publish(msg);
We broadcast the image to anyone connected to one of our topics, exactly as we would have using a ros::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
Now let's write a simple image subscriber.






