image_timeline_renderer.py
Go to the documentation of this file.
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 sys
00038 import threading
00039 import time
00040 
00041 import wx
00042 
00043 import Image
00044 
00045 from rxbag import bag_helper, TimelineCache, TimelineRenderer
00046 
00047 import image_helper
00048 
00049 class ImageTimelineRenderer(TimelineRenderer):
00050     """
00051     Draws thumbnails of sensor_msgs/Image or sensor_msgs/CompressedImage in the timeline.
00052     """
00053     def __init__(self, timeline, thumbnail_height=160):
00054         TimelineRenderer.__init__(self, timeline, msg_combine_px=40.0)
00055 
00056         self.thumbnail_height     = thumbnail_height
00057 
00058         self.thumbnail_combine_px = 20.0                 # use cached thumbnail if it's less than this many pixels away
00059         self.min_thumbnail_width  = 8                    # don't display thumbnails if less than this many pixels across
00060         self.quality              = Image.NEAREST        # quality hint for thumbnail scaling
00061 
00062         self.thumbnail_cache = TimelineCache(self._load_thumbnail, lambda topic, msg_stamp, thumbnail: wx.CallAfter(self.timeline.Refresh))
00063 
00064     # TimelineRenderer implementation
00065 
00066     def get_segment_height(self, topic):
00067         return self.thumbnail_height
00068 
00069     def draw_timeline_segment(self, dc, topic, stamp_start, stamp_end, x, y, width, height):
00070         max_interval_thumbnail = self.timeline.map_dx_to_dstamp(self.thumbnail_combine_px)
00071         
00072         max_interval_thumbnail = max(0.1, max_interval_thumbnail)
00073 
00074         thumbnail_gap = 6
00075 
00076         thumbnail_x, thumbnail_y, thumbnail_height = x + 1, y + 1, height - 2 - thumbnail_gap  # leave 1px border
00077 
00078         dc.set_source_rgb(1, 1, 1)
00079         dc.rectangle(x, y, width, height - thumbnail_gap)
00080         dc.fill()
00081 
00082         thumbnail_width = None
00083         thumbnail_right = None
00084             
00085         while True:
00086             available_width = (x + width) - thumbnail_x
00087 
00088             # Check for enough remaining to draw thumbnail
00089             if width > 1 and available_width < self.min_thumbnail_width:
00090                 break
00091 
00092             # Try to display the thumbnail, if its right edge is to the right of the timeline's left side
00093             if not thumbnail_width or thumbnail_x + thumbnail_width >= self.timeline.history_left:
00094                 stamp = self.timeline.map_x_to_stamp(thumbnail_x, clamp_to_visible=False)
00095     
00096                 thumbnail_bitmap = self.thumbnail_cache.get_item(topic, stamp, max_interval_thumbnail)
00097     
00098                 # Cache miss
00099                 if not thumbnail_bitmap:
00100                     thumbnail_details = (thumbnail_height,)
00101                     self.thumbnail_cache.enqueue((topic, stamp, max_interval_thumbnail, thumbnail_details))
00102 
00103                     if not thumbnail_width:
00104                         break
00105                 else:
00106                     thumbnail_width = thumbnail_bitmap.get_width()
00107 
00108                     if width > 1:
00109                         if available_width < thumbnail_width:
00110                             # Space remaining, but have to chop off thumbnail
00111                             thumbnail_width = available_width - 1
00112         
00113                     dc.set_source_surface(thumbnail_bitmap, thumbnail_x, thumbnail_y)
00114                     dc.rectangle(thumbnail_x, thumbnail_y, thumbnail_width, thumbnail_height)
00115                     dc.fill()
00116 
00117             thumbnail_x += thumbnail_width
00118 
00119             if width == 1:
00120                 break
00121 
00122         # Draw 1px black border
00123         dc.set_line_width(1)
00124         dc.set_source_rgb(0, 0, 0)
00125         if width == 1:
00126             dc.rectangle(x, y, thumbnail_x - x, height - thumbnail_gap - 1)
00127         else:
00128             dc.rectangle(x, y, width, height - thumbnail_gap - 1)
00129         dc.stroke()
00130 
00131         return True
00132     
00133     def close(self):
00134         if self.thumbnail_cache:
00135             self.thumbnail_cache.stop()
00136             self.thumbnail_cache.join()
00137 
00138     #
00139 
00140     def _load_thumbnail(self, topic, stamp, thumbnail_details):
00141         """
00142         Loads the thumbnail from the bag
00143         """
00144         (thumbnail_height,) = thumbnail_details
00145         
00146         # Find position of stamp using index
00147         t = rospy.Time.from_sec(stamp)
00148         bag, entry = self.timeline.get_entry(t, topic)
00149         if not entry:
00150             return None, None
00151         pos = entry.position
00152 
00153         # Not in the cache; load from the bag file
00154         
00155         with self.timeline._bag_lock:
00156             msg_topic, msg, msg_stamp = bag._read_message(pos)
00157         
00158         # Convert from ROS image to PIL image
00159         try:
00160             pil_image = image_helper.imgmsg_to_pil(msg)
00161         except Exception, ex:
00162             print >> sys.stderr, 'Error loading image on topic %s: %s' % (topic, str(ex)) 
00163             return None, None
00164         
00165         if not pil_image:
00166             return None, None
00167         
00168         # Calculate width to maintain aspect ratio
00169         try:
00170             pil_image_size = pil_image.size
00171             thumbnail_width = int(round(thumbnail_height * (float(pil_image_size[0]) / pil_image_size[1])))
00172     
00173             # Scale to thumbnail size
00174             thumbnail = pil_image.resize((thumbnail_width, thumbnail_height), self.quality)
00175     
00176             # Convert from PIL Image to Cairo ImageSurface
00177             thumbnail_bitmap = image_helper.pil_to_cairo(thumbnail)
00178             
00179             return msg_stamp, thumbnail_bitmap
00180         
00181         except Exception, ex:
00182             print >> sys.stderr, 'Error loading image on topic %s: %s' % (topic, str(ex))
00183             raise
00184             return None, None


rxbag_plugins
Author(s): Tim Field
autogenerated on Mon Jan 6 2014 11:54:21