Note: This tutorial assumes that you have completed the previous tutorials: Writing a Simple Image Publisher, Writing a Simple Image Subscriber.
(!) 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.

Running the Simple Image Publisher and Subscriber with Different Transports

Description: This tutorial discusses running the simple image publisher and subscriber using multiple transports.

Tutorial Level: BEGINNER

Next Tutorial: Managing Transport Plugins

Running the Publisher

Make sure that a roscore is up and running:

$ roscore

In a previous tutorial we made a publisher node called "my_publisher"; now run the node with an image file as the command-line argument:

$ rosrun image_transport_tutorial my_publisher path/to/some/image.jpg

To check that your node is running properly, list the topics being published:

$ rostopic list -v

Look for /camera/image in the output, which should look something like:

Published topics:
 * /rosout [roslib/Log] 1 publisher
 * /camera/image [sensor_msgs/Image] 1 publisher
 * /rosout_agg [roslib/Log] 1 publisher

Subscribed topics:
 * /rosout [roslib/Log] 1 subscriber

If you have non-default transport plugins built, you may see additional published topics in the /camera/image/ namespace.

Running the Subscriber

In the last tutorial, we made a subscriber node called "my_subscriber"; now run it:

$ rosrun image_transport_tutorial my_subscriber

You should see a window pop up with the image you gave to the publisher.

Let's look at the node graph:

$ rosrun rqt_graph rqt_graph

transport_graph.png

Changing the Transport Used

Currently our nodes are communicating raw sensor_msgs/Image messages, so we are not gaining anything over using ros::Publisher and ros::Subscriber. Let's change that by introducing a new transport.

The compressed_image_transport package provides plugins for the "compressed" transport, which sends images over the wire in either JPEG- or PNG-compressed form. Notice that compressed_image_transport is not a dependency of your package; image_transport will automatically discover all transport plugins built in your ROS system.

Shut down your publisher node and restart it. If you list the published topics again, you should see a new one:

 * /camera/image/compressed [sensor_msgs/CompressedImage] 1 publisher

Now let's start up a new subscriber, this one using compressed transport. The key is that image_transport subscribers check the parameter ~image_transport for the name of a transport to use in place of "raw". Let's set this parameter and start a subscriber node with name "compressed_listener":

$ rosparam set /compressed_listener/image_transport compressed
$ rosrun image_transport_tutorial my_subscriber __name:=compressed_listener

You should see an identical image window pop up. Let's check the node graph again:

$ rosrun rqt_graph rqt_graph

transport_graph_with_compressed.png

compressed_listener is listening to a separate topic carrying JPEG-compressed versions of the same images published on /camera/image.

Note that if you just want the compressed image, you can change the parameter globally in-line:

$ rosrun image_transport_tutorial my_subscriber _image_transport:=compressed

Changing Transport-Specific Behavior

For a particular transport, we may want to tweak settings such as compression level, bit rate, etc. Transport plugins can expose such settings through rqt_reconfigure. For example, /camera/image/compressed allows you to change the compression format and quality on the fly; see the package documentation for full details.

For now let's adjust the JPEG quality. By default, "compressed" transport uses JPEG compression at 80% quality; let's change it to 15%:

$ rosrun rqt_reconfigure rqt_reconfigure

Now pick /camera/image/compressed in the drop-down menu and move the jpeg_quality slider down to 15%. Do you see the compression artifacts in your second view window?

Dynamic Reconfigure has updated the dynamically reconfigurable parameter /camera/image/compressed/jpeg_quality. You can verify this by running:

$ rosparam get /camera/image/compressed/jpeg_quality

This should display 15.

Wiki: image_transport/Tutorials/ExaminingImagePublisherSubscriber (last edited 2015-01-04 08:30:04 by alexandre_willame)