ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Is it possible to convert depth messages as Ipl image using CvBridge

asked 2014-12-16 23:00:07 -0500

shravan gravatar image

updated 2014-12-18 11:43:42 -0500

I could convert RGB messages in to picture but says that the "[32FC1] is not a color format. but [mono8] is. The conversion does not make sense". Is there anything else i should be doing?

my code

import roslib
from matplotlib import pyplot as plt
roslib.load_manifest('beginner_tutorials')
import sys
import rospy
import cv2
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import numpy as np
i=0
np.set_printoptions(threshold='nan')
def callback(data):
 try:
        cv_image = CvBridge().imgmsg_to_cv2(data, "32FC1")
 except CvBridgeError, e:
        print e 
 global i
 cv_image1 = np.array(cv_image, dtype=np.float)
 cv2.normalize(cv_image1, cv_image1, 0, 1, cv2.NORM_MINMAX)
 cv_image1=cv_image1*2**16

 cv2.imwrite("im"+str(i)+".jpg")
     i+=1

def video():

rospy.init_node('video', anonymous=True)

im=rospy.Subscriber('/camera/depth_registered/image_rect', Image, callback)

rospy.spin()
if __name__ == '__main__':
   video()
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2014-12-17 01:28:35 -0500

Wolf gravatar image

updated 2014-12-18 07:37:23 -0500

Your question: Is it possible to convert depth messages as Ipl image using CvBridge? Yes, definitely! But: for the rest of your question: It depends! ;)

In the first place the resulting IplImage (or better to use cv::Mat) will have the same color space as the incoming image, i. e. if you call cv_bridge::toCvShare(msg) or toCVCopy without encoding a published "32FC1" image will result in an "32FC1" (32bit floating point, one channel). For some color spaces cv_bridge can handle the color transformation, i. e. your can call cv_bridge::toCvShare(msg, your_encoding ) where your encoding must not necessarily be the encoding of the original image message ( e. g. rgb8 <---> bgr8 ); However, this does not work for all encoding combinations!

Apparently, if you get an error it does not work for the transformation you desired! Therefore, you should read your the image first without specifying an encoding (cv_bridge::toCvShare(msg) ) and that do your desired transformation yourself. The image callback of rqt_image_view gives a good example of how to do this, see: https://github.com/ros-visualization/...

Commenting on your edit: I am not familiar with opencv python but I commented your code where it seams unclear:

        cv_image = CvBridge().imgmsg_to_cv2(data, "16UC1")  ## was your image not 32 float? 
                                                            ## this means 16 unsigned integer
 except CvBridgeError, e:
        print e 
 global i
 cv_image1 = np.array(cv_image, dtype=np.float)  ## type float again? 
                                                 ## up there you converted to unsigned int 16!
edit flag offensive delete link more

Comments

@Wolf Thanks for the suggestion.It helped me to convert depth messages to opencv images but after saving it shows me a black image. When i Googled ,it told me that 32FC1 images cannot be stored and I am not sure how to convert it into a 8bit or 16 bit data to store it. Is it possible to do it

shravan gravatar image shravan  ( 2014-12-17 12:32:12 -0500 )edit

And I used Opencv python for this conversion

shravan gravatar image shravan  ( 2014-12-17 12:34:30 -0500 )edit

Does rqt_image_view properly scale your images? you cannot directly convert 32 bit floating point image to 8 Bit images; you have to scale/quantify in some kind of way so you can see what is going on...

Wolf gravatar image Wolf  ( 2014-12-18 04:36:47 -0500 )edit

@Wolf i have added my code. When I try this out I get an image but it is distorted . I guess Opencv does not take 16 bit images. Is there any possibility write images of 16bit type

shravan gravatar image shravan  ( 2014-12-18 05:31:03 -0500 )edit

@Wolf . Sorry for that, it is my mistake .I have corrected it .Now have a look

shravan gravatar image shravan  ( 2014-12-18 11:46:07 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-12-16 23:00:07 -0500

Seen: 4,090 times

Last updated: Dec 18 '14