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 (Android Java)
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, Java, Android
Tutorial Level: INTERMEDIATE
TODO:
TODO: Need to compleate this tutorial and documentation in github code.
github = https://github.com/talregev/android_cv_bridge
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 Java API 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 CvImage cv_image = CvImage.toCvCopy(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:
The use of "encoding" is slightly more complicated in this case. It does, as before, refer to the IplImage. 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 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 /*
2 * Copyright (c) 2015, Tal Regev
3 * All rights reserved.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 *
8 * * Redistributions of source code must retain the above copyright
9 * notice, this list of conditions and the following disclaimer.
10 * * Redistributions in binary form must reproduce the above copyright
11 * notice, this list of conditions and the following disclaimer in the
12 * documentation and/or other materials provided with the distribution.
13 * * Neither the name of the Android Sensors Driver nor the names of its
14 * contributors may be used to endorse or promote products derived from
15 * this software without specific prior written permission.
16 *
17 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 * POSSIBILITY OF SUCH DAMAGE.
28 */
29
30 package org.ros.android.android_tutorial_cv_bridge;
31
32 import android.os.Bundle;
33 import android.util.Log;
34 import android.view.WindowManager;
35
36 import org.opencv.android.BaseLoaderCallback;
37 import org.opencv.android.LoaderCallbackInterface;
38 import org.opencv.android.OpenCVLoader;
39 import org.opencv.core.Core;
40 import org.opencv.core.Point;
41 import org.opencv.core.Scalar;
42 import org.ros.android.RosActivity;
43 import org.ros.message.MessageListener;
44 import org.ros.namespace.GraphName;
45 import org.ros.node.ConnectedNode;
46 import org.ros.node.Node;
47 import org.ros.node.NodeConfiguration;
48 import org.ros.node.NodeMain;
49 import org.ros.node.NodeMainExecutor;
50 import org.ros.node.topic.Publisher;
51 import org.ros.node.topic.Subscriber;
52
53 import java.io.IOException;
54
55 import cv_bridge.CvImage;
56 import sensor_msgs.Image;
57
58
59 /**
60 * @author Tal Regev
61 */
62 public class MainActivity extends RosActivity implements NodeMain{
63
64 protected Publisher<Image> imagePublisher;
65 protected Subscriber<Image> imageSubscriber;
66 protected ConnectedNode node;
67 protected static final String TAG = "cv_bridge Tutorial";
68 protected boolean isInit = false;
69
70
71 public MainActivity() {
72 // The RosActivity constructor configures the notification title and ticker
73 // messages.
74 super("cv_bridge Tutorial", "cv_bridge Tutorial");
75 }
76
77 @SuppressWarnings("unchecked")
78 @Override
79 public void onCreate(Bundle savedInstanceState) {
80 super.onCreate(savedInstanceState);
81 getWindow().addFlags(WindowManager.LayoutParams.FLAG_KEEP_SCREEN_ON);
82 setContentView(R.layout.main);
83 }
84
85 @Override
86 protected void init(NodeMainExecutor nodeMainExecutor) {
87 // At this point, the user has already been prompted to either enter the URI
88 // of a master to use or to start a master locally.
89
90 // The user can easily use the selected ROS Hostname in the master chooser
91 // activity.
92 NodeConfiguration nodeConfiguration = NodeConfiguration.newPublic(getRosHostname());
93 nodeConfiguration.setMasterUri(getMasterUri());
94 nodeMainExecutor.execute(this, nodeConfiguration);
95 isInit = true;
96 onResume();
97 }
98
99 @Override
100 public GraphName getDefaultNodeName() {
101 return GraphName.of("android_tutorial_cv_bridge");
102 }
103
104 protected boolean isOpenCVInit = false;
105 protected BaseLoaderCallback mLoaderCallback = new BaseLoaderCallback(this) {
106 @Override
107 public void onManagerConnected(int status) {
108 switch (status) {
109 case LoaderCallbackInterface.SUCCESS: {
110 Log.i(TAG, "OpenCV loaded successfully");
111 isOpenCVInit = true;
112 }
113 break;
114 default: {
115 super.onManagerConnected(status);
116 }
117 break;
118 }
119 }
120 };
121
122 @Override
123 public void onStart(ConnectedNode connectedNode) {
124 this.node = connectedNode;
125 final org.apache.commons.logging.Log log = node.getLog();
126 imagePublisher = node.newPublisher("/image_converter/output_video", Image._TYPE);
127 imageSubscriber = node.newSubscriber("/camera/image_raw", Image._TYPE);
128 imageSubscriber.addMessageListener(new MessageListener<Image>() {
129 @Override
130 public void onNewMessage(Image message) {
131 if (isOpenCVInit) {
132 CvImage cvImage;
133 try {
134 cvImage = CvImage.toCvCopy(message);
135 } catch (Exception e) {
136 log.error("cv_bridge exception: " + e.getMessage());
137 return;
138 }
139 //make sure the picture is bug enough for my circle.
140 if (cvImage.image.rows() > 110 && cvImage.image.cols() > 110) {
141 //place the circle in the middle of the picture with radius 100 and color blue.
142 Core.circle(cvImage.image, new Point(cvImage.image.cols()/2, cvImage.image.rows()/2), 100, new Scalar(255, 0, 0));
143 }
144 try {
145 imagePublisher.publish(cvImage.toImageMsg(imagePublisher.newMessage()));
146 } catch (IOException e) {
147 log.error("cv_bridge exception: " + e.getMessage());
148 }
149 }
150 }
151 });
152
153 Log.i(TAG, "called onStart");
154 }
155
156 @Override
157 public void onResume() {
158 super.onResume();
159 if (isInit) {
160 OpenCVLoader.initAsync(OpenCVLoader.OPENCV_VERSION_2_4_9, this, mLoaderCallback);
161 }
162 }
163
164 @Override
165 public void onShutdown(Node node) {
166 }
167
168 @Override
169 public void onShutdownComplete(Node node) {
170 }
171
172 @Override
173 public void onError(Node node, Throwable throwable) {
174 }
175 }
1 import cv_bridge.CvImage;
All of OpenCV is included by import org.opencv.*.
You should always wrap your call to cvImage.toImageMsg() 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 "/camera/image_raw".
You can see whether your node is correctly publishing images over ros using either rostopic or by viewing the images using image_view.