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