$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2009, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 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 = Image.open(StringIO(img_msg.data)) 00049 if pil_img.mode != 'L': 00050 pil_img = pil_bgr2rgb(pil_img) 00051 else: 00052 alpha = False 00053 if img_msg.encoding == 'mono8': 00054 mode = 'L' 00055 elif img_msg.encoding == 'rgb8': 00056 mode = 'BGR' 00057 elif img_msg.encoding == 'bgr8': 00058 mode = 'RGB' 00059 elif img_msg.encoding in ['bayer_rggb8', 'bayer_bggr8', 'bayer_gbrg8', 'bayer_grbg8']: 00060 mode = 'L' 00061 elif img_msg.encoding == 'mono16': 00062 if img_msg.is_bigendian: 00063 mode = 'F;16B' 00064 else: 00065 mode = 'F:16' 00066 elif img_msg.encoding == 'rgba8': 00067 mode = 'BGR' 00068 alpha = True 00069 elif img_msg.encoding == 'bgra8': 00070 mode = 'RGB' 00071 alpha = True 00072 00073 pil_img = Image.frombuffer('RGB', (img_msg.width, img_msg.height), img_msg.data, 'raw', mode, 0, 1) 00074 00075 if rgba and pil_img.mode != 'RGBA': 00076 pil_img = pil_img.convert('RGBA') 00077 00078 return pil_img 00079 00080 except Exception, ex: 00081 print >> sys.stderr, 'Can\'t convert image: %s' % ex 00082 return None 00083 00084 def pil_bgr2rgb(pil_img): 00085 rgb2bgr = (0, 0, 1, 0, 00086 0, 1, 0, 0, 00087 1, 0, 0, 0) 00088 return pil_img.convert('RGB', rgb2bgr) 00089 00090 def imgmsg_to_wx(img_msg): 00091 # Can use rgb8 encoding directly 00092 if img_msg.encoding == 'rgb8': 00093 return wx.ImageFromBuffer(img_msg.width, img_msg.height, img_msg.data) 00094 00095 pil_img = imgmsg_to_pil(img_msg) 00096 if not pil_img: 00097 return None 00098 00099 return wx.ImageFromData(pil_img.size[0], pil_img.size[1], pil_img.tostring()) 00100 00101 def pil_to_cairo(pil_img): 00102 w, h = pil_img.size 00103 data = array.array('c') 00104 data.fromstring(pil_img.tostring()) 00105 00106 return cairo.ImageSurface.create_for_data(data, cairo.FORMAT_ARGB32, w, h) 00107 00108 def wxbitmap_to_cairo(bitmap): 00109 image = wx.ImageFromBitmap(bitmap) 00110 pil_img = Image.new('RGB', (image.GetWidth(), image.GetHeight())) 00111 pil_img.fromstring(image.GetData()) 00112 00113 pil_img = pil_bgr2rgb(pil_img) 00114 if pil_img.mode != 'RGBA': 00115 pil_img = pil_img.convert('RGBA') 00116 00117 return pil_to_cairo(pil_img)