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 PKG = 'rxbag_plugins'
00034 import roslib; roslib.load_manifest(PKG)
00035 import rospy
00036
00037 import array
00038 from cStringIO import StringIO
00039 import sys
00040
00041 import Image
00042 import wx
00043 import cairo
00044
00045 def imgmsg_to_pil(img_msg, rgba=True):
00046 try:
00047 if img_msg._type == 'sensor_msgs/CompressedImage':
00048 pil_img = pil_bgr2rgb(Image.open(StringIO(img_msg.data)))
00049 else:
00050 alpha = False
00051 if img_msg.encoding == 'mono8':
00052 mode = 'L'
00053 elif img_msg.encoding == 'rgb8':
00054 mode = 'BGR'
00055 elif img_msg.encoding == 'bgr8':
00056 mode = 'RGB'
00057 elif img_msg.encoding in ['bayer_rggb8', 'bayer_bggr8', 'bayer_gbrg8', 'bayer_grbg8']:
00058 mode = 'L'
00059 elif img_msg.encoding == 'mono16':
00060 if img_msg.is_bigendian:
00061 mode = 'F;16B'
00062 else:
00063 mode = 'F:16'
00064 elif img_msg.encoding == 'rgba8':
00065 mode = 'BGR'
00066 alpha = True
00067 elif img_msg.encoding == 'bgra8':
00068 mode = 'RGB'
00069 alpha = True
00070
00071 pil_img = Image.frombuffer('RGB', (img_msg.width, img_msg.height), img_msg.data, 'raw', mode, 0, 1)
00072
00073 if rgba and pil_img.mode != 'RGBA':
00074 pil_img = pil_img.convert('RGBA')
00075
00076 return pil_img
00077
00078 except Exception, ex:
00079 print >> sys.stderr, 'Can\'t convert:', mode, ex
00080 return None
00081
00082 def pil_bgr2rgb(pil_img):
00083 rgb2bgr = (0, 0, 1, 0,
00084 0, 1, 0, 0,
00085 1, 0, 0, 0)
00086 return pil_img.convert('RGB', rgb2bgr)
00087
00088 def imgmsg_to_wx(img_msg):
00089
00090 if img_msg.encoding == 'rgb8':
00091 return wx.ImageFromBuffer(img_msg.width, img_msg.height, img_msg.data)
00092
00093 pil_img = imgmsg_to_pil(img_msg)
00094 if not pil_img:
00095 return None
00096
00097 return wx.ImageFromData(pil_img.size[0], pil_img.size[1], pil_img.tostring())
00098
00099 def pil_to_cairo(pil_img):
00100 w, h = pil_img.size
00101 data = array.array('c')
00102 data.fromstring(pil_img.tostring())
00103
00104 return cairo.ImageSurface.create_for_data(data, cairo.FORMAT_ARGB32, w, h)
00105
00106 def wxbitmap_to_cairo(bitmap):
00107 image = wx.ImageFromBitmap(bitmap)
00108 pil_img = Image.new('RGB', (image.GetWidth(), image.GetHeight()))
00109 pil_img.fromstring(image.GetData())
00110
00111 pil_img = pil_bgr2rgb(pil_img)
00112 if pil_img.mode != 'RGBA':
00113 pil_img = pil_img.convert('RGBA')
00114
00115 return pil_to_cairo(pil_img)