[Documentation] [TitleIndex] [WordIndex

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 IplImage format.

You will also learn how to convert OpenCV images to ROS format to be published over ROS.

cvbridge3.png

Converting ROS image messages to OpenCV images

To convert a ROS image message into an IplImage, the class sensor_msgs::CvBridge provides the following member function:

   1 IplImage* imgMsgToCv(sensor_msgs::Image::ConstPtr image_message,
   2                      string cv_encoding="passthrough")

The input is the image message pointer, as well as an optional cv_encoding. The encoding refers to the destination IplImage image.

If the default value of "passthrough" is given, the destination image encoding will be the same as the image message encoding. Image encodings can be any one of the following OpenCV image encodings:

For popular image encodings, CvBridge will optionally do color or pixel depth conversions as necessary. To use this feature, specify the cv_encoding to be one of the following strings:

Note that mono8 and bgr8 are the two image encodings expected by most OpenCV functions.

Converting OpenCV images to ROS image messages

To convert an IplImage into a ROS image message, CvBridge provides the following function:

   1 sensor_msgs::Image::Ptr cvToImgMsg(const IplImage* cv_image,
   2                                    string cv_encoding="passthrough")

The use of "encoding" is slightly more complicated in this case. It does, as before, refer to the IplImage. However, cvToImgMsg() does not do any conversions for you (use cvCvtColor and cvConvertScale instead). The ROS image message must always have the same number of channels and pixel depth as the IplImage. However, the special commonly used image formats above (bgr8, rgb8, etc.) will insert information into the image message about the channel ordering. In this way, future consumers will know whether the image they receive is RGB or BGR.

An example ROS node

Here is a node that listens to a ROS image message topic, converts the images into an IplImage, 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 "sensor_msgs/Image.h"
   3 #include "image_transport/image_transport.h"
   4 #include "cv_bridge/CvBridge.h"
   5 #include <opencv/cv.h>
   6 #include <opencv/highgui.h>
   7 
   8 class ImageConverter {
   9 
  10 public:
  11 
  12 ImageConverter(ros::NodeHandle &n) :
  13   n_(n), it_(n_)
  14 {
  15   image_pub_ = it_.advertise("image_topic_2",1);
  16 
  17   cvNamedWindow("Image window");
  18   image_sub_ = it_.subscribe(
  19     "image_topic", 1, &ImageConverter::imageCallback, this);
  20 }
  21 
  22 ~ImageConverter()
  23 {
  24   cvDestroyWindow("Image window");
  25 }
  26 
  27 void imageCallback(const sensor_msgs::ImageConstPtr& msg_ptr)
  28 {
  29 
  30   IplImage *cv_image = NULL;
  31   try
  32   {
  33     cv_image = bridge_.imgMsgToCv(msg_ptr, "bgr8");
  34   }
  35   catch (sensor_msgs::CvBridgeException error)
  36   {
  37     ROS_ERROR("error");
  38   }
  39 
  40   if (cv_image->width > 60 && cv_image->height > 60)
  41     cvCircle(cv_image, cvPoint(50,50), 10, cvScalar(255));
  42 
  43   cvShowImage("Image window", cv_image);
  44   cvWaitKey(3);
  45 
  46   try
  47   {
  48     image_pub_.publish(bridge_.cvToImgMsg(cv_image, "bgr8"));
  49   }
  50   catch (sensor_msgs::CvBridgeException error)
  51   {
  52     ROS_ERROR("error");
  53   }
  54 
  55 }
  56 
  57 protected:
  58 
  59 ros::NodeHandle n_;
  60 image_transport::ImageTransport it_;
  61 image_transport::Subscriber image_sub_;
  62 sensor_msgs::CvBridge bridge_;
  63 image_transport::Publisher image_pub_;
  64 
  65 };
  66 
  67 int main(int argc, char** argv)
  68 {
  69   ros::init(argc, argv, "image_converter");
  70   ros::NodeHandle n;
  71   ImageConverter ic(n);
  72   ros::spin();
  73   return 0;
  74 }

Let's break down the above node:

   2 #include "sensor_msgs/Image.h"
   3 

Includes the ROS image message type. Remember to include sensor_msgs in your manifest.

   3 #include "image_transport/image_transport.h"
   4 

Includes the header for transporting images in ROS, remember to include image_transport in your manifest. Allows you to subscribe to raw or compressed images. See image_transport for more information.

   4 #include "cv_bridge/CvBridge.h"
   5 

Includes the header for CvBridge. Remember to include opencv2 and cv_bridge in your manifest.

   5 #include <opencv/cv.h>
   6 #include <opencv/highgui.h>
   7 

Includes OpenCV. cv.h contains the definition of an IplImage, while highgui.h contains the headers for display.

  62 sensor_msgs::CvBridge bridge_;

Our node will need an instance of CvBridge, which lives in the sensor_msgs namespace.

  30   IplImage *cv_image = NULL;
  31   try
  32   {
  33     cv_image = bridge_.imgMsgToCv(msg_ptr, "bgr8");
  34   }
  35   catch (sensor_msgs::CvBridgeException error)
  36   {
  37     ROS_ERROR("error");
  38   }

Converting an image message pointer to an OpenCV message only requires a call to the function imgMsgToCv(). This takes in the shared pointer to the image directly, as well as the encoding of the destination OpenCV image.

You should always wrap your call to imgMsgToCv() to catch conversion errors.

Note that you should not call cvReleaseImage() on your IplImage*. CvBridge will clean up the IplImage for you.

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 the image stream topic to the "image_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.

  46   try
  47   {
  48     image_pub_.publish(bridge_.cvToImgMsg(cv_image, "bgr8"));
  49   }
  50   catch (sensor_msgs::CvBridgeException error)
  51   {
  52     ROS_ERROR("error");
  53   }

The edited image is converted back to ROS image message format using cvToImgMsg with the encoding "bgr8", so future subscribers will know the color order.

You can see whether your node is correctly publishing images over ros using either rostopic or by viewing the images using image_view.


2024-02-24 12:31