cv1.py
Go to the documentation of this file.
00001 import roslib
00002 roslib.load_manifest('hrl_opencv')
00003 #from sensor_msgs.msg import Image as RosImage
00004 from std_msgs.msg import UInt8MultiArray
00005 from std_msgs.msg import MultiArrayLayout
00006 from std_msgs.msg import MultiArrayDimension
00007 
00008 import opencv as cv
00009 import opencv.highgui as hg
00010 import opencv.adaptors as ad
00011 import Image as pil
00012 import numpy as np
00013 
00014 #################################################################################################################
00015 # ROS Utility Functions
00016 #################################################################################################################
00017 
00018 ##
00019 # Convert from ROS to OpenCV image datatype
00020 # @param image to convert
00021 def ros2cv(image):
00022     #ros to pil then pil to opencv
00023     #if image.encoding != 'bgr' and image.encoding != 'rgb' and image.encoding != 'bgr8':
00024     channels = 1
00025     if image.encoding != 'bgr8':
00026         raise RuntimeError('Unsupported format "%s"' % image.encoding)
00027     else:
00028         channels = 3
00029     if image.is_bigendian != 0:
00030         raise RuntimeError('Unsupported endianess')
00031 
00032     #print image.encoding
00033     #print image.step
00034     #print image.is_bigendian
00035     #if image.depth != 'uint8':
00036     #    raise RuntimeError('Unsupported depth "%s"' % image.depth)
00037 
00038     #height    = image.data.layout.dim[0].size
00039     #width     = image.data.layout.dim[1].size
00040     #channels  = image.data.layout.dim[2].size
00041     #print 'expected', image.width * channels
00042     #print 'step', image.step
00043     #print 'image.width', image.width, image.height
00044     assert(image.width * channels == image.step)
00045     height = image.height
00046     width  = image.width
00047     np_image = np.reshape(np.fromstring(image.data, dtype='uint8', count=height*width*channels), [height, width, 3])
00048     #np
00049     #np_image[:,:,2].A1
00050     #np_image[:,:,1].A1
00051     #np_image[:,:,0].A1
00052     np_image2 = np.empty(np_image.shape, dtype='uint8')
00053     np_image2[:, :, 0] = np_image[:, :, 2]
00054     np_image2[:, :, 1] = np_image[:, :, 1]
00055     np_image2[:, :, 2] = np_image[:, :, 0]
00056 
00057     #concatenated = np.concatenate([np_image[:,:,2].flatten(), np_image[:,:,1].flatten(), np_image[:,:,0].flatten()], axis=0)
00058     #print 2050*2448*3
00059     #print concatenated.shape
00060     #np_image2 = np.reshape(np.concatenate([np_image[:,:,0].flatten(), np_image[:,:,1].flatten(), np_image[:,:,2].flatten()], axis=0), [3, width, height])
00061     #np_image2 = np.swapaxes(np_image2, 0, 2)
00062     #print np_image[:,:,2].shape
00063     #print 'datatype:', np_image2.dtype
00064     #print np_image2.shape
00065     return ad.NumPy2Ipl(np_image2)
00066     #return None
00067 
00068 #################################################################################################################
00069 # Highgui 
00070 #################################################################################################################
00071 
00072 ##
00073 # Simple drawing of text on an image with a drop shadow
00074 def text(image, x, y, a_string):
00075     font = cv.cvInitFont(CV_FONT_HERSHEY_SIMPLEX, .3, .3)
00076     cv.cvPutText(image, a_string, cv.cvPoint(x, y),     font, cv.cvScalar(0,0,0))
00077     cv.cvPutText(image, a_string, cv.cvPoint(x+1, y+1), font, cv.cvScalar(255,255,255))
00078 
00079 def clone_image(image):
00080     return cv.cvCloneImage(image)
00081 
00082 def save_image(name, image):
00083     hg.cvSaveImage(name, image)
00084 
00085 def show_image(name, image):
00086     hg.cvShowImage(name, image)
00087 
00088 def named_window(name):
00089     hg.cvNamedWindow(name, hg.CV_WINDOW_AUTOSIZE)
00090 
00091 def wait_key(msecs=33):
00092     return hg.cvWaitKey(msecs)
00093 
00094 #################################################################################################################
00095 # CXCore 
00096 #################################################################################################################
00097 
00098 #################################################################################################################
00099 # CVAux 
00100 #################################################################################################################
00101 
00102 #################################################################################################################
00103 # Machine Learning 
00104 #################################################################################################################
00105 
00106 #################################################################################################################
00107 # CVReference 
00108 #################################################################################################################
00109 ##
00110 # Morphological closing
00111 def morpho_close(cv_image, n_times=1):
00112     dst  = cv.cvCloneImage(cv_image)
00113     dst2 = cv.cvCloneImage(cv_image)
00114     cv.cvDilate(cv_image, dst, None, n_times)
00115     cv.cvErode(dst, dst2, None, n_times)
00116     return dst2
00117 
00118 ##
00119 # Morphological opening
00120 def morpho_open(cv_image, n_times=1):
00121     dst  = cv.cvCloneImage(cv_image)
00122     dst2 = cv.cvCloneImage(cv_image)
00123     cv.cvErode(cv_image, dst, None, n_times)
00124     cv.cvDilate(dst, dst2, None, n_times)
00125     return dst2
00126 
00127 ##
00128 # Morphological opening
00129 def dilate(cv_image, n_times=1):
00130     dst  = cv.cvCloneImage(cv_image)
00131     cv.cvDilate(cv_img, dst, None, n_times)
00132     return dst
00133 
00134 ##
00135 # Morphological opening
00136 def erode(cv_image, n_times=1):
00137     dst  = cv.cvCloneImage(cv_image)
00138     cv.cvErode(cv_img, dst, None, n_times)
00139     return dst
00140 
00141 
00142 ##
00143 # Mask a color image with a given black and white mask
00144 # @param img
00145 # @param img_mask one channeled image
00146 # @return color image with masked part filled with black
00147 def mask(img, img_mask):
00148     dim      = img.width, img.height
00149     depth    = img.depth
00150     channels = img.nChannels
00151 
00152     r_chan = cv.cvCreateImage(cv.cvSize(*dim), depth, 1)
00153     g_chan = cv.cvCreateImage(cv.cvSize(*dim), depth, 1)
00154     b_chan = cv.cvCreateImage(cv.cvSize(*dim), depth, 1)
00155     combined = cv.cvCreateImage(cv.cvSize(*dim), depth, 3)
00156     cv.cvSplit(img, r_chan, g_chan, b_chan, None)
00157 
00158     cv.cvAnd(r_chan, img_mask, r_chan)
00159     cv.cvAnd(g_chan, img_mask, g_chan)
00160     cv.cvAnd(b_chan, img_mask, b_chan)
00161     cv.cvMerge(r_chan, g_chan, b_chan, None, combined)
00162     return combined
00163 
00164 ##
00165 # Split a color image into its component parts
00166 def split(image):
00167     img1 = cv.cvCreateImage(cv.cvSize(image.width, image.height), 8, 1)
00168     img2 = cv.cvCreateImage(cv.cvSize(image.width, image.height), 8, 1)
00169     img3 = cv.cvCreateImage(cv.cvSize(image.width, image.height), 8, 1)
00170     cv.cvSplit(image, img1, img2, img3, None)
00171     return (img1, img2, img3)
00172 
00173 ##
00174 # Easy scaling of an image by factor s
00175 # @param image
00176 # @param s
00177 def scale(image, s):
00178     scaled = cv.cvCreateImage(cv.cvSize(int(image.width * s), int(image.height * s)), image.depth, image.nChannels)
00179     cv.cvResize(image, scaled, cv.CV_INTER_AREA)
00180     return scaled
00181 
00182 if __name__ == '__main__':
00183     import opencv.highgui as hg
00184     import rospy
00185     from photo.srv import *
00186     #a = create_ros_image()
00187     #print a
00188 
00189     rospy.wait_for_service('/photo/capture')
00190     say_cheese = rospy.ServiceProxy('/photo/capture', Capture)
00191     ros_img = say_cheese().image
00192     print dir(ros_img)
00193     cv_img = ros2cv(ros_img)
00194     hg.cvSaveImage('test.png', cv_img)
00195 
00196 #def create_ros_image(width=1, height=1, channels=2, data='12'):
00197 #    d1 = MultiArrayDimension(label='height',   size=height,   stride=width*height*channels)
00198 #    d2 = MultiArrayDimension(label='width',    size=width,    stride=width*channels)
00199 #    d3 = MultiArrayDimension(label='channels', size=channels, stride=channels)
00200 #
00201 #    layout     = MultiArrayLayout(dim = [d1,d2,d3])
00202 #    multiarray = UInt8MultiArray(layout=layout, data=data)
00203 #    return RosImage(label='image', encoding='bgr', depth='uint8', uint8_data=multiarray)
00204 
00205 ###
00206 ## Fill holes in a binary image using scipy
00207 ##
00208 #def fill_holes(cv_img):
00209 #    img_np     = ut.cv2np(cv_img)
00210 #    img_binary = img_np[:,:,0]
00211 #    results    = ni.binary_fill_holes(img_binary)
00212 #    img_cv     = ut.np2cv(np_mask2np_image(results))
00213 #    return img_cv


hrl_opencv
Author(s): Hai Nguyen, Advait Jain (Healthcare Robotics Lab, Georgia Tech)
autogenerated on Wed Nov 27 2013 11:36:49