Contents
Concepts
ROS passes around images in its own sensor_msgs/Image message format, but many users will want to use images in conjunction with OpenCV. CvBridge is a ROS library that provides an interface between ROS and OpenCV. CvBridge can be found in the cv_bridge package in the vision_opencv stack.
In this tutorial, you will learn how to write a node that uses CvBridge to convert ROS images into OpenCV cv::Mat format.
You will also learn how to convert OpenCV images to ROS format to be published over ROS.
Tutorials(2f)UsingCvBridgeCppDiamondback/cvbridge4.png) 
 
Converting ROS image messages to OpenCV images
CvBridge defines a CvImage type containing an OpenCV image, its encoding and a ROS header. CvImage contains exactly the information sensor_msgs/Image does, so we can convert either representation to the other.
When converting a ROS sensor_msgs/Image message into a CvImage, CvBridge recognizes two distinct use cases:
- We want to modify the data in-place. We have to make a copy of the ROS message data.
- We won't modify the data. We can safely share the data owned by the ROS message instead of copying.
CvBridge provides the following functions for converting to CvImage:
   1 // Case 1: Always copy, returning a mutable CvImage
   2 CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr& source,
   3                     const std::string& encoding = std::string());
   4 CvImagePtr toCvCopy(const sensor_msgs::Image& source,
   5                     const std::string& encoding = std::string());
   6 
   7 // Case 2: Share if possible, returning a const CvImage
   8 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr& source,
   9                           const std::string& encoding = std::string());
  10 CvImageConstPtr toCvShare(const sensor_msgs::Image& source,
  11                           const boost::shared_ptr<void const>& tracked_object,
  12                           const std::string& encoding = std::string());
The input is the image message pointer, as well as an optional encoding argument. The encoding refers to the destination CvImage.
toCvCopy creates a copy of the image data from the ROS message, even when the source and destination encodings match. However, you are free to modify the returned CvImage.
toCvShare will point the returned cv::Mat at the ROS message data, avoiding a copy, if the source and destination encodings match. As long as you hold a copy of the returned CvImage, the ROS message data will not be freed. If the encodings do not match, it will allocate a new buffer and perform the conversion. You are not permitted to modify the returned CvImage, as it may share data with the ROS image message, which in turn may be shared with other callbacks. Note: the second overload of toCvShare is more convenient when you have a pointer to some other message type (e.g. stereo_msgs/DisparityImage) that contains a sensor_msgs/Image you want to convert.
If no encoding (or rather, the empty string) is given, the destination image encoding will be the same as the image message encoding. In this case toCvShare is guaranteed to not copy the image data. Image encodings can be any one of the following OpenCV image encodings:
- 8UC[1-4]
- 8SC[1-4]
- 16UC[1-4]
- 16SC[1-4]
- 32SC[1-4]
- 32FC[1-4]
- 64FC[1-4]
For popular image encodings, CvBridge will optionally do color or pixel depth conversions as necessary. To use this feature, specify the encoding to be one of the following strings:
- mono8: CV_8UC1, grayscale image 
- mono16: CV_16UC1, 16-bit grayscale image 
- bgr8: CV_8UC3, color image with blue-green-red color order 
- rgb8: CV_8UC3, color image with red-green-blue color order 
- bgra8: CV_8UC4, BGR color image with an alpha channel 
- rgba8: CV_8UC4, RGB color image with an alpha channel 
Note that mono8 and bgr8 are the two image encodings expected by most OpenCV functions.
Finally, CvBridge will recognize Bayer pattern encodings as having OpenCV type 8UC1 (8-bit unsigned, one channel). It will not perform conversions to or from Bayer pattern; in a typical ROS system, this is done instead by image_proc. CvBridge recognizes the following Bayer encodings:
- bayer_rggb8 
- bayer_bggr8 
- bayer_gbrg8 
- bayer_grbg8 
Converting OpenCV images to ROS image messages
To convert a CvImage into a ROS image message, use one the toImageMsg() member function:
If the CvImage is one you have allocated yourself, don't forget to fill in the header and encoding fields.
An example ROS node
Here is a node that listens to a ROS image message topic, converts the image into a cv::Mat, draws a circle on it and displays the image using OpenCV. The image is then republished over ROS.
In your manifest (or when you use roscreate-pkg), add the following dependencies:
sensor_msgs opencv2 cv_bridge roscpp std_msgs image_transport
   1 #include <ros/ros.h>
   2 #include <image_transport/image_transport.h>
   3 #include <cv_bridge/cv_bridge.h>
   4 #include <sensor_msgs/image_encodings.h>
   5 #include <opencv2/imgproc/imgproc.hpp>
   6 #include <opencv2/highgui/highgui.hpp>
   7 
   8 namespace enc = sensor_msgs::image_encodings;
   9 
  10 static const char WINDOW[] = "Image window";
  11 
  12 class ImageConverter
  13 {
  14   ros::NodeHandle nh_;
  15   image_transport::ImageTransport it_;
  16   image_transport::Subscriber image_sub_;
  17   image_transport::Publisher image_pub_;
  18 
  19 public:
  20   ImageConverter()
  21     : it_(nh_)
  22   {
  23     image_pub_ = it_.advertise("out", 1);
  24     image_sub_ = it_.subscribe("in", 1, &ImageConverter::imageCb, this);
  25 
  26     cv::namedWindow(WINDOW);
  27   }
  28 
  29   ~ImageConverter()
  30   {
  31     cv::destroyWindow(WINDOW);
  32   }
  33 
  34   void imageCb(const sensor_msgs::ImageConstPtr& msg)
  35   {
  36     cv_bridge::CvImagePtr cv_ptr;
  37     try
  38     {
  39       cv_ptr = cv_bridge::toCvCopy(msg, enc::BGR8);
  40     }
  41     catch (cv_bridge::Exception& e)
  42     {
  43       ROS_ERROR("cv_bridge exception: %s", e.what());
  44       return;
  45     }
  46 
  47     if (cv_ptr->image.rows > 60 && cv_ptr->image.cols > 60)
  48       cv::circle(cv_ptr->image, cv::Point(50, 50), 10, CV_RGB(255,0,0));
  49 
  50     cv::imshow(WINDOW, cv_ptr->image);
  51     cv::waitKey(3);
  52 
  53     image_pub_.publish(cv_ptr->toImageMsg());
  54   }
  55 };
  56 
  57 int main(int argc, char** argv)
  58 {
  59   ros::init(argc, argv, "image_converter");
  60   ImageConverter ic;
  61   ros::spin();
  62   return 0;
  63 }
Let's break down the above node:
Error: No code_block found Using image_transport for publishing and subscribing to images in ROS allows you to subscribe to compressed image streams. Remember to include image_transport in your manifest.
Error: No code_block found Includes the header for CvBridge as well as some useful constants and functions related to image encodings. Remember to include cv_bridge in your manifest.
Error: No code_block found Includes the headers for OpenCV's image processing and GUI modules. Remember to include opencv2 in your manifest.
Error: No code_block found Subscribe to an image topic "in" and advertise an image topic "out" using image_transport.
Error: No code_block found OpenCV HighGUI calls to create/destroy a display window on start-up/shutdown.
Error: No code_block found In our subscriber callback, we first convert the ROS image message to a CvImage suitable for working with OpenCV. Since we're going to draw on the image, we need a mutable copy of it, so we use toCvCopy(). sensor_msgs::image_encodings::BGR8 is simply a constant for "bgr8", but less susceptible to typos.
Note that OpenCV expects color images to use BGR channel order.
You should always wrap your calls to toCvCopy() / toCvShared() to catch conversion errors as those functions will not check for the validity of your data.
Error: No code_block found Draw a red circle on the image, then show it in the display window.
Error: No code_block found Convert the CvImage to a ROS image message and publish it on the "out" topic.
To run the node, you will need an image stream. Run a camera or play a bag file to generate the image stream. Now you can run this node, remapping "in" to the actual image stream topic.
If you have successfully converted images to OpenCV format, you will see a HighGui window with the name "Image window" and your image+circle displayed.
You can see whether your node is correctly publishing images over ROS using either rostopic or by viewing the images using image_view.
Examples of sharing the image data
In the complete example above, we explicitly copied the image data, but sharing (when possible) is equally easy:
   1 namespace enc = sensor_msgs::image_encodings;
   2 
   3 void imageCb(const sensor_msgs::ImageConstPtr& msg)
   4 {
   5   cv_bridge::CvImageConstPtr cv_ptr;
   6   try
   7   {
   8     cv_ptr = cv_bridge::toCvShare(msg, enc::BGR8);
   9   }
  10   catch (cv_bridge::Exception& e)
  11   {
  12     ROS_ERROR("cv_bridge exception: %s", e.what());
  13     return;
  14   }
  15 
  16   // Process cv_ptr->image using OpenCV
  17 }
If the incoming message has "bgr8" encoding, cv_ptr will alias its data without making a copy. If it has a different but convertible encoding, say "mono8", CvBridge will allocate a new buffer for cv_ptr and perform the conversion. Without the exception handling this would only be one line of code, but then an incoming message with a malformed (or unsupported) encoding would bring down the node. For example, if the incoming image is from the image_raw topic for a Bayer pattern camera, CvBridge will throw an exception because it (intentionally) does not support automatic Bayer-to-color conversion.
A slightly more complicated example:
   1 namespace enc = sensor_msgs::image_encodings;
   2 
   3 void imageCb(const sensor_msgs::ImageConstPtr& msg)
   4 {
   5   cv_bridge::CvImageConstPtr cv_ptr;
   6   try
   7   {
   8     if (enc::isColor(msg->encoding))
   9       cv_ptr = cv_bridge::toCvShare(msg, enc::BGR8);
  10     else
  11       cv_ptr = cv_bridge::toCvShare(msg, enc::MONO8);
  12   }
  13   catch (cv_bridge::Exception& e)
  14   {
  15     ROS_ERROR("cv_bridge exception: %s", e.what());
  16     return;
  17   }
  18 
  19   // Process cv_ptr->image using OpenCV
  20 }
In this case we want to use color if available, otherwise falling back to monochrome. If the incoming image is either "bgr8" or "mono8", we avoid copying data.
