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