33 from __future__
import print_function
36 from cStringIO
import StringIO
38 from io
import StringIO
42 from PIL
import ImageOps
48 if img_msg._type ==
'sensor_msgs/CompressedImage':
49 pil_img = Image.open(StringIO(img_msg.data))
50 if pil_img.mode !=
'L':
55 if img_msg.encoding ==
'mono8':
57 elif img_msg.encoding ==
'rgb8':
59 elif img_msg.encoding ==
'bgr8':
61 elif img_msg.encoding
in [
'bayer_rggb8',
'bayer_bggr8',
'bayer_gbrg8',
'bayer_grbg8']:
63 elif img_msg.encoding ==
'mono16' or img_msg.encoding ==
'16UC1':
65 if img_msg.is_bigendian:
69 elif img_msg.encoding ==
'rgba8':
72 elif img_msg.encoding ==
'bgra8':
76 raise Exception(
"Unsupported image format: %s" % img_msg.encoding)
77 pil_img = Image.frombuffer(
78 pil_mode, (img_msg.width, img_msg.height), img_msg.data,
'raw', mode, 0, 1)
81 if pil_img.mode ==
'F':
82 pil_img = pil_img.point(
lambda i: i * (1. / 256.)).convert(
'L')
83 pil_img = ImageOps.autocontrast(pil_img)
85 if rgba
and pil_img.mode !=
'RGBA':
86 pil_img = pil_img.convert(
'RGBA')
90 except Exception
as ex:
91 print(
'Can\'t convert image: %s' % ex, file=sys.stderr)
96 rgb2bgr = (0, 0, 1, 0,
99 return pil_img.convert(
'RGB', rgb2bgr)
104 data = array.array(
'c')
105 data.fromstring(pil_img.tostring())
107 return cairo.ImageSurface.create_for_data(data, cairo.FORMAT_ARGB32, w, h)
def pil_to_cairo(pil_img)
def imgmsg_to_pil(img_msg, rgba=True)