Note: This tutorial assumes that you have completed the previous tutorials: image_transport Beginner Tutorials, pluginlib. |
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 New Transport
Description: This tutorials covers how to write publisher and subscriber plugins for a new image transport option.Tutorial Level: INTERMEDIATE
NOTE: This tutorial is incomplete.
Contents
Overview
The real power of image_transport comes from its extensibility. Nodes using image_transport to publish and receive images can take advantage of new transports without so much as a recompile. In this tutorial we will see how to write our own transport for a very simple kind of "compression": subsampling on the publisher side, then supersampling back to the original dimensions on the client side.
There are four steps to writing a transport:
Define your transport-specific message type. For example, a streaming video transport would use some Packet type for internal communication.
Write your publisher plugin. This encodes a sensor_msgs/Image into one or more instances of the transport-specific message type and publishes them on the dedicated transport topic.
Write your subscriber plugin. This listens on the transport topic and decodes the transport-specific messages back into sensor_msgs/Image messages passed to the user callback.
Register your transport plugins so that image_transport can find them.
The above outline assumes that your transport uses a single ROS topic for all publisher-subscriber communication, which should normally be the case. This assumption allows us to use the C++ base classes SimplePublisherPlugin and SimpleSubscriberPlugin. These classes take care of all the scaffolding and bookkeeping so that we can simply get on with writing our encoding and decoding functions. If for some reason your transport requires a more exotic communication structure, it is possible (but much less pleasant!) to subclass the lower-level base classes PublisherPlugin and SubscriberPlugin instead.
The code for that tutorial is in the tutorial folder of image_transport at: https://github.com/ros-perception/image_common
Defining the Message Type
Create msg/ResizedImage.msg in package learning_image_transport with your favorite editor, and place the following inside it:
uint32 original_height uint32 original_width sensor_msgs/Image image
Our message is very simple: we store the subsampled image along with its original dimensions, so that we can later restore it (with some loss of information, of course).
Writing a Simple Publisher Plugin
The Code
Create include/image_transport_tutorial/resized_publisher.h and place the following inside it:
1 #include <image_transport/simple_publisher_plugin.h>
2 #include "learning_image_transport/ResizedImage.h"
3
4 class ResizedPublisher : public image_transport::SimplePublisherPlugin<learning_image_transport::ResizedImage>
5 {
6 public:
7 virtual std::string getTransportName() const
8 {
9 return "resized";
10 }
11
12 protected:
13 virtual void publish(const sensor_msgs::Image& message,
14 const PublishFn& publish_fn) const;
15 };
Next create src/resized_publisher.cpp and place the following inside it:
1 #include <image_transport_tutorial/resized_publisher.h>
2 #include <opencv2/imgproc/imgproc.hpp>
3 #include <cv_bridge/cv_bridge.h>
4
5 void ResizedPublisher::publish(const sensor_msgs::Image& message,
6 const PublishFn& publish_fn) const
7 {
8 cv::Mat cv_image;
9 boost::shared_ptr<void const> tracked_object;
10 try
11 {
12 cv_image = cv_bridge::toCvShare(message, tracked_object, message.encoding)->image;
13 }
14 catch (cv::Exception &e)
15 {
16 ROS_ERROR("Could not convert from '%s' to '%s'.", message.encoding.c_str(), message.encoding.c_str());
17 return;
18 }
19
20 // Retrieve subsampling factor from the parameter server
21 double subsampling_factor;
22 std::string param_name;
23 nh().param<double>("resized_image_transport_subsampling_factor", subsampling_factor, 2.0);
24
25 // Rescale image
26 int new_width = cv_image.cols / subsampling_factor + 0.5;
27 int new_height = cv_image.rows / subsampling_factor + 0.5;
28 cv::Mat buffer;
29 cv::resize(cv_image, buffer, cv::Size(new_width, new_height));
30
31 // Set up ResizedImage and publish
32 image_transport_tutorial::ResizedImage resized_image;
33 resized_image.original_height = cv_image.rows;
34 resized_image.original_width = cv_image.cols;
35 resized_image.image = *(cv_bridge::CvImage(message.header, "bgr8", cv_image).toImageMsg());
36 publish_fn(resized_image);
37 }
The Code Explained
Starting with resized_publisher.h:
We include the headers for our base class and transport-specific message type.
4 class ResizedPublisher : public image_transport::SimplePublisherPlugin<learning_image_transport::ResizedImage>
We declare our publisher plugin class, inheriting from SimplePublisherPlugin. SimplePublisherPlugin is templated on the transport-specific message type.
SimplePublisherPlugin requires us to implement only two functions, and one of them is dead simple! getTransportName() returns the name of the transport; we have chosen "resized".
The other required function is an internal (protected) version of publish(). This is where we encode the sensor_msgs/Image argument into a ResizedImage and publish it. But what is that PublishFn argument? This type is defined by SimplePublisherPlugin. PublishFn is a function object that takes our transport-specific message type as an argument and publishes it using some ROS primitive.
Why this indirection? It turns out that in ROS there are two distinct ways to publish messages to a subscriber. The normal way is to broadcast a message to all subscribers; the other way, seldom used, is to publish a message to a single subscriber within a subscriber status callback. SimplePublisherPlugin performs some tricky plumbing to use our implementation of publish() in both cases.
For the details of publish(), the code is self-explanatory.
Writing a Simple Subscriber Plugin
The Code
Create include/learning_image_transport/resized_subscriber.h and place the following inside it:
1 #include <image_transport/simple_subscriber_plugin.h>
2 #include <image_transport_tutorial/ResizedImage.h>
3
4 class ResizedSubscriber : public image_transport::SimpleSubscriberPlugin<image_transport_tutorial::ResizedImage>
5 {
6 public:
7 virtual ~ResizedSubscriber() {}
8
9 virtual std::string getTransportName() const
10 {
11 return "resized";
12 }
13
14 protected:
15 virtual void internalCallback(const typename image_transport_tutorial::ResizedImage::ConstPtr& message,
16 const Callback& user_cb);
17 };
Next create src/resized_subscriber.cpp and place the following inside it:
1 #include <image_transport_tutorial/resized_subscriber.h>
2 #include <cv_bridge/cv_bridge.h>
3 #include <opencv2/imgproc/imgproc.hpp>
4
5 void ResizedSubscriber::internalCallback(const image_transport_tutorial::ResizedImage::ConstPtr& msg,
6 const Callback& user_cb)
7 {
8 // This is only for optimization, not to copy the image
9 boost::shared_ptr<void const> tracked_object_tmp;
10 cv::Mat img_rsz = cv_bridge::toCvShare(msg->image, tracked_object_tmp)->image;
11 // Resize the image to its original size
12 cv::Mat img_restored;
13 cv::resize(img_rsz, img_restored, cv::Size(msg->original_width, msg->original_height));
14
15 // Call the user callback with the restored image
16 cv_bridge::CvImage cv_img(msg->image.header, msg->image.encoding, img_restored);
17 user_cb(cv_img.toImageMsg());
18 };
The Code Explained
Registering the Transport Plugins
We have written our transport plugins, but some steps remain to register them with ROS so that image_transport can find them. For details on these steps, see pluginlib; below we will note only features of special relevance to image_transport.
Adding to the Plugin List
Create src/manifest.cpp and place the following inside it:
1 #include <pluginlib/class_list_macros.h>
2 #include <image_transport_tutorial/resized_publisher.h>
3 #include <image_transport_tutorial/resized_subscriber.h>
4
5 PLUGINLIB_REGISTER_CLASS(resized_pub, ResizedPublisher, image_transport::PublisherPlugin)
6
7 PLUGINLIB_REGISTER_CLASS(resized_sub, ResizedSubscriber, image_transport::SubscriberPlugin)
We register our plugin classes as resized_pub and resized_sub. These names follow an important convention; image_transport assumes that for a transport named <foo>, the publisher and subscriber plugins have respective lookup names <foo>_pub and <foo>_sub.
We register our plugins as instances of the low-level base classes PublisherPlugin and SubscriberPlugin. The "simple" base classes we used in our code subclass PublisherPlugin and SubscriberPlugin to provide a more convenient high-level interface.
Writing the Plugin Description File
Now create resized_plugins.xml in the learning_image_transport/ directory and place the following inside it:
<library path="lib/libresized_image_transport"> <class name="resized_pub" type="ResizedPublisher" base_class_type="image_transport::PublisherPlugin"> <description> This plugin publishes a decimated version of the image. </description> </class> <class name="resized_sub" type="ResizedSubscriber" base_class_type="image_transport::SubscriberPlugin"> <description> This plugin rescales a decimated image to its original size. </description> </class> </library>
This file helps ROS to automatically discover, load and reason about our plugins.
Exporting the Plugins
Finally, we must point to our plugin description file within the package Manifest. Insert the following lines in your package.xml:
Building Your Transport
In your CMakeLists.txt, uncomment rosbuild_genmsg() (to generate our ResizedImage message) and build our plugins as a library:
cmake_minimum_required(VERSION 2.8) project(image_transport_tutorial) find_package(catkin REQUIRED cv_bridge genmsg image_transport sensor_msgs) # add the resized image message add_message_files(DIRECTORY msg FILES ResizedImage.msg ) generate_messages(DEPENDENCIES sensor_msgs) catkin_package() find_package(OpenCV) include_directories(include ${OpenCV_INCLUDE_DIRS}) # add the plugin examples add_library(resized_publisher src/manifest.cpp src/resized_publisher.cpp src/resized_subscriber.cpp) target_link_libraries(resized_publisher ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})