(!) 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.

Converting between ROS images and OpenCV images (Python)

Description: This tutorial describes how to interface ROS and OpenCV by converting ROS images into OpenCV images, and vice versa, using cv_bridge. Included is a sample node that can be used as a template for your own node.

Keywords: image, images, OpenCV, cvbridge, CvBridge

Tutorial Level: INTERMEDIATE

Next Tutorial: Converting between ROS images and OpenCV images (Android Java)

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.

cvbridge3.png

Converting ROS image messages to OpenCV images

To convert a ROS image message into an cv::Mat, module cv_bridge.CvBridge provides the following function:

   1 from cv_bridge import CvBridge
   2 bridge = CvBridge()
   3 cv_image = bridge.imgmsg_to_cv2(image_message, desired_encoding='passthrough')

The input is the image message, as well as an optional encoding. The encoding refers to the destination cv::Mat 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:

  • 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.

Converting OpenCV images to ROS image messages

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

   1 from cv_bridge import CvBridge
   2 bridge = CvBridge()
   3 image_message = bridge.cv2_to_imgmsg(cv_image, encoding="passthrough")

The use of "encoding" is slightly more complicated in this case. It does, as before, refer to the cv::Mat. However, cv2_to_imgmsg() does not do any conversions for you (use CvtColor and ConvertScale instead). The ROS image message must always have the same number of channels and pixel depth as the cv::Mat. 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 cv::Mat, draws a circle on it and displays the image using OpenCV. The image is then republished over ROS.

In your manifest (alternatively when using roscreate-pkg or catkin_create_pkg), add the following dependencies:

sensor_msgs
opencv2
cv_bridge
rospy
std_msgs

(Kinetic users, please see the compatibility section below.)

   1 #!/usr/bin/env python
   2 from __future__ import print_function
   3 
   4 import roslib
   5 roslib.load_manifest('my_package')
   6 import sys
   7 import rospy
   8 import cv2
   9 from std_msgs.msg import String
  10 from sensor_msgs.msg import Image
  11 from cv_bridge import CvBridge, CvBridgeError
  12 
  13 class image_converter:
  14 
  15   def __init__(self):
  16     self.image_pub = rospy.Publisher("image_topic_2",Image)
  17 
  18     self.bridge = CvBridge()
  19     self.image_sub = rospy.Subscriber("image_topic",Image,self.callback)
  20 
  21   def callback(self,data):
  22     try:
  23       cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
  24     except CvBridgeError as e:
  25       print(e)
  26 
  27     (rows,cols,channels) = cv_image.shape
  28     if cols > 60 and rows > 60 :
  29       cv2.circle(cv_image, (50,50), 10, 255)
  30 
  31     cv2.imshow("Image window", cv_image)
  32     cv2.waitKey(3)
  33 
  34     try:
  35       self.image_pub.publish(self.bridge.cv2_to_imgmsg(cv_image, "bgr8"))
  36     except CvBridgeError as e:
  37       print(e)
  38 
  39 def main(args):
  40   ic = image_converter()
  41   rospy.init_node('image_converter', anonymous=True)
  42   try:
  43     rospy.spin()
  44   except KeyboardInterrupt:
  45     print("Shutting down")
  46   cv2.destroyAllWindows()
  47 
  48 if __name__ == '__main__':
  49     main(sys.argv)

Don't forget to chmod +x your file.

Error: No code_block found All of OpenCV is included by importing cv. In the manifest, add a dependency to opencv2 and cv_bridge.

Error: No code_block found CvBridge also lives in cv_bridge.

Error: No code_block found Converting an image message pointer to an OpenCV message only requires a call to the function imgmsg_to_cv2(). This takes in the image message, as well as the encoding of the destination OpenCV image.

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

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". For example, "/camera/rgb/image_color".

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.

Error: No code_block found The edited image is converted back to ROS image message format using cv2_to_imgmsg() 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.

ROS-Kinetic Compatibility

Since ROS Kinetic, the default supported version is OpenCV 3. In order to run this tutorial on Kinetic, you should find_package the version 2 in your CMakeLists.txt (see here). You should ensure that OpenCV 2 is installed in your system (libopencv-dev on Ubuntu 16.04).

Then you can run the example code above. However, since OpenCV2 is not a ROS package anymore, you can't add it to catkin dependence. Hence, the list of dependent packages in your manifest should be:

sensor_msgs
cv_bridge
rospy
std_msgs

Wiki: cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython (last edited 2020-06-12 21:57:44 by JohnStechschulte)