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
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 IplImage format.
You will also learn how to convert OpenCV images to ROS format to be published over ROS.
Converting ROS image messages to OpenCV images
To convert a ROS image message into an IplImage, module cv_bridge.CvBridge provides the following function:
1 cv_image = bridge.imgmsg_to_cv(image_message, desired_encoding="passthrough")
The input is the image message, as well as an optional 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:
- 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 IplImage into a ROS image message, CvBridge provides the following function:
1 image_message = cv_to_imgmsg(cv_image, encoding="passthrough")
The use of "encoding" is slightly more complicated in this case. It does, as before, refer to the IplImage. However, cv_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 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 rospy std_msgs
1 #!/usr/bin/env python
2 import roslib
3 roslib.load_manifest('my_package')
4 import sys
5 import rospy
6 import cv
7 from std_msgs.msg import String
8 from sensor_msgs.msg import Image
9 from cv_bridge import CvBridge, CvBridgeError
10
11 class image_converter:
12
13 def __init__(self):
14 self.image_pub = rospy.Publisher("image_topic_2",Image)
15
16 cv.NamedWindow("Image window", 1)
17 self.bridge = CvBridge()
18 self.image_sub = rospy.Subscriber("image_topic",Image,self.callback)
19
20 def callback(self,data):
21 try:
22 cv_image = self.bridge.imgmsg_to_cv(data, "bgr8")
23 except CvBridgeError, e:
24 print e
25
26 (cols,rows) = cv.GetSize(cv_image)
27 if cols > 60 and rows > 60 :
28 cv.Circle(cv_image, (50,50), 10, 255)
29
30 cv.ShowImage("Image window", cv_image)
31 cv.WaitKey(3)
32
33 try:
34 self.image_pub.publish(self.bridge.cv_to_imgmsg(cv_image, "bgr8"))
35 except CvBridgeError, e:
36 print e
37
38 def main(args):
39 ic = image_converter()
40 rospy.init_node('image_converter', anonymous=True)
41 try:
42 rospy.spin()
43 except KeyboardInterrupt:
44 print "Shutting down"
45 cv.DestroyAllWindows()
46
47 if __name__ == '__main__':
48 main(sys.argv)
Don't forget to chmod +x your file.
6 import cv
All of OpenCV is included by importing cv. In the manifest, add a dependency to opencv2 and cv_bridge.
9 from cv_bridge import CvBridge, CvBridgeError
CvBridge also lives in cv_bridge.
Converting an image message pointer to an OpenCV message only requires a call to the function imgmsg_to_cv(). 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_cv() 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".
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.
The edited image is converted back to ROS image message format using cv_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.






