Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 import array
00034 from cStringIO import StringIO
00035 import sys
00036
00037 from PIL import Image
00038 from PIL import ImageOps
00039 import cairo
00040
00041
00042 def imgmsg_to_pil(img_msg, rgba=True):
00043 try:
00044 if img_msg._type == 'sensor_msgs/CompressedImage':
00045 pil_img = Image.open(StringIO(img_msg.data))
00046 if pil_img.mode != 'L':
00047 pil_img = pil_bgr2rgb(pil_img)
00048 else:
00049 alpha = False
00050 pil_mode = 'RGB'
00051 if img_msg.encoding == 'mono8':
00052 mode = 'L'
00053 elif img_msg.encoding == 'rgb8':
00054 mode = 'RGB'
00055 elif img_msg.encoding == 'bgr8':
00056 mode = 'BGR'
00057 elif img_msg.encoding in ['bayer_rggb8', 'bayer_bggr8', 'bayer_gbrg8', 'bayer_grbg8']:
00058 mode = 'L'
00059 elif img_msg.encoding == 'mono16' or img_msg.encoding == '16UC1':
00060 pil_mode = 'F'
00061 if img_msg.is_bigendian:
00062 mode = 'F;16B'
00063 else:
00064 mode = 'F;16'
00065 elif img_msg.encoding == 'rgba8':
00066 mode = 'BGR'
00067 alpha = True
00068 elif img_msg.encoding == 'bgra8':
00069 mode = 'RGB'
00070 alpha = True
00071 else:
00072 raise Exception("Unsupported image format: %s" % img_msg.encoding)
00073 pil_img = Image.frombuffer(pil_mode, (img_msg.width, img_msg.height), img_msg.data, 'raw', mode, 0, 1)
00074
00075
00076 if pil_img.mode == 'F':
00077 pil_img = pil_img.point(lambda i: i*(1./256.)).convert('L')
00078 pil_img = ImageOps.autocontrast(pil_img)
00079
00080 if rgba and pil_img.mode != 'RGBA':
00081 pil_img = pil_img.convert('RGBA')
00082
00083 return pil_img
00084
00085 except Exception, ex:
00086 print >> sys.stderr, 'Can\'t convert image: %s' % ex
00087 return None
00088
00089
00090 def pil_bgr2rgb(pil_img):
00091 rgb2bgr = (0, 0, 1, 0,
00092 0, 1, 0, 0,
00093 1, 0, 0, 0)
00094 return pil_img.convert('RGB', rgb2bgr)
00095
00096
00097 def pil_to_cairo(pil_img):
00098 w, h = pil_img.size
00099 data = array.array('c')
00100 data.fromstring(pil_img.tostring())
00101
00102 return cairo.ImageSurface.create_for_data(data, cairo.FORMAT_ARGB32, w, h)