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 rospy
00034
00035 import sys
00036
00037 from PIL import Image
00038 from PIL.ImageQt import ImageQt
00039
00040 from rqt_bag import TimelineCache, TimelineRenderer
00041
00042 import image_helper
00043
00044 from python_qt_binding.QtCore import Qt
00045 from python_qt_binding.QtGui import QBrush, QPen, QPixmap
00046
00047
00048 class ImageTimelineRenderer(TimelineRenderer):
00049 """
00050 Draws thumbnails of sensor_msgs/Image or sensor_msgs/CompressedImage in the timeline.
00051 """
00052 def __init__(self, timeline, thumbnail_height=160):
00053 super(ImageTimelineRenderer, self).__init__(timeline, msg_combine_px=40.0)
00054
00055 self.thumbnail_height = thumbnail_height
00056
00057 self.thumbnail_combine_px = 20.0
00058 self.min_thumbnail_width = 8
00059 self.quality = Image.NEAREST
00060
00061 self.thumbnail_cache = TimelineCache(self._load_thumbnail, lambda topic, msg_stamp, thumbnail: self.timeline.scene().update())
00062
00063
00064 def get_segment_height(self, topic):
00065 return self.thumbnail_height
00066
00067 def draw_timeline_segment(self, painter, topic, stamp_start, stamp_end, x, y, width, height):
00068 """
00069 draws a stream of images for the topic
00070 :param painter: painter object, ''QPainter''
00071 :param topic: topic to draw, ''str''
00072 :param stamp_start: stamp to start drawing, ''rospy.Time''
00073 :param stamp_end: stamp to end drawing, ''rospy.Time''
00074 :param x: x to draw images at, ''int''
00075 :param y: y to draw images at, ''int''
00076 :param width: width in pixels of the timeline area, ''int''
00077 :param height: height in pixels of the timeline area, ''int''
00078 """
00079 if x < self.timeline._history_left:
00080 width += x - self.timeline._history_left
00081 x = self.timeline._history_left
00082 max_interval_thumbnail = self.timeline.map_dx_to_dstamp(self.thumbnail_combine_px)
00083 max_interval_thumbnail = max(0.1, max_interval_thumbnail)
00084 thumbnail_gap = 6
00085 thumbnail_x, thumbnail_y, thumbnail_height = x + 1, y + 1, height - 2 - thumbnail_gap
00086
00087
00088 painter.setBrush(QBrush(Qt.white))
00089 painter.drawRect(x, y, width, height - thumbnail_gap)
00090 thumbnail_width = None
00091
00092 while True:
00093 available_width = (x + width) - thumbnail_x
00094
00095
00096 if width > 1 and available_width < self.min_thumbnail_width:
00097 break
00098
00099
00100 if not thumbnail_width or thumbnail_x + thumbnail_width >= self.timeline._history_left:
00101 stamp = self.timeline.map_x_to_stamp(thumbnail_x, clamp_to_visible=False)
00102 thumbnail_bitmap = self.thumbnail_cache.get_item(topic, stamp, max_interval_thumbnail)
00103
00104
00105 if not thumbnail_bitmap:
00106 thumbnail_details = (thumbnail_height,)
00107 self.thumbnail_cache.enqueue((topic, stamp, max_interval_thumbnail, thumbnail_details))
00108 if not thumbnail_width:
00109 break
00110 else:
00111 thumbnail_width, _ = thumbnail_bitmap.size
00112
00113 if width > 1:
00114 if available_width < thumbnail_width:
00115 thumbnail_width = available_width - 1
00116 QtImage = ImageQt(thumbnail_bitmap)
00117 pixmap = QPixmap.fromImage(QtImage)
00118 painter.drawPixmap(thumbnail_x, thumbnail_y, thumbnail_width, thumbnail_height, pixmap)
00119 thumbnail_x += thumbnail_width
00120
00121 if width == 1:
00122 break
00123
00124 painter.setPen(QPen(QBrush(Qt.black)))
00125 painter.setBrush(QBrush(Qt.transparent))
00126 if width == 1:
00127 painter.drawRect(x, y, thumbnail_x - x, height - thumbnail_gap - 1)
00128 else:
00129 painter.drawRect(x, y, width, height - thumbnail_gap - 1)
00130 return True
00131
00132 def close(self):
00133 if self.thumbnail_cache:
00134 self.thumbnail_cache.stop()
00135 self.thumbnail_cache.join()
00136
00137 def _load_thumbnail(self, topic, stamp, thumbnail_details):
00138 """
00139 Loads the thumbnail from the bag
00140 """
00141 (thumbnail_height,) = thumbnail_details
00142
00143
00144 t = rospy.Time.from_sec(stamp)
00145 bag, entry = self.timeline.scene().get_entry(t, topic)
00146 if not entry:
00147 return None, None
00148 pos = entry.position
00149
00150
00151
00152 with self.timeline.scene()._bag_lock:
00153 msg_topic, msg, msg_stamp = bag._read_message(pos)
00154
00155
00156 try:
00157 pil_image = image_helper.imgmsg_to_pil(msg)
00158 except Exception, ex:
00159 print >> sys.stderr, 'Error loading image on topic %s: %s' % (topic, str(ex))
00160 pil_image = None
00161
00162 if not pil_image:
00163 print >> sys.stderr, 'Disabling renderer on %s' % topic
00164 self.timeline.set_renderer_active(topic, False)
00165 return None, None
00166
00167
00168 try:
00169 pil_image_size = pil_image.size
00170 thumbnail_width = int(round(thumbnail_height * (float(pil_image_size[0]) / pil_image_size[1])))
00171
00172 thumbnail = pil_image.resize((thumbnail_width, thumbnail_height), self.quality)
00173
00174 return msg_stamp, thumbnail
00175
00176 except Exception, ex:
00177 print >> sys.stderr, 'Error loading image on topic %s: %s' % (topic, str(ex))
00178 raise
00179 return None, None