33 from __future__
import print_function
38 from python_qt_binding
import QT_BINDING_MODULES
40 not QT_BINDING_MODULES[
'QtCore'].__name__.startswith(
'PyQt5')
and
41 'PyQt5' in sys.modules
43 sys.modules[
'PyQt5'] =
None
45 from PIL.ImageQt
import ImageQt
47 from rqt_bag
import TimelineCache, TimelineRenderer
49 from rqt_bag_plugins
import image_helper
51 from python_qt_binding.QtCore
import Qt
52 from python_qt_binding.QtGui
import QBrush, QPen, QPixmap
58 Draws thumbnails of sensor_msgs/Image or sensor_msgs/CompressedImage in the timeline.
61 def __init__(self, timeline, thumbnail_height=160):
62 super(ImageTimelineRenderer, self).
__init__(timeline, msg_combine_px=40.0)
71 self.
_load_thumbnail,
lambda topic, msg_stamp, thumbnail: self.timeline.scene().update())
79 draws a stream of images for the topic
80 :param painter: painter object, ''QPainter''
81 :param topic: topic to draw, ''str''
82 :param stamp_start: stamp to start drawing, ''rospy.Time''
83 :param stamp_end: stamp to end drawing, ''rospy.Time''
84 :param x: x to draw images at, ''int''
85 :param y: y to draw images at, ''int''
86 :param width: width in pixels of the timeline area, ''int''
87 :param height: height in pixels of the timeline area, ''int''
89 if x < self.timeline._history_left:
90 width += x - self.timeline._history_left
91 x = self.timeline._history_left
93 max_interval_thumbnail = max(0.1, max_interval_thumbnail)
96 thumbnail_x, thumbnail_y, thumbnail_height = x + 1, y + 1, height - 2 - thumbnail_gap
99 painter.setBrush(QBrush(Qt.white))
100 painter.drawRect(x, y, width, height - thumbnail_gap)
101 thumbnail_width =
None
104 available_width = (x + width) - thumbnail_x
112 if not thumbnail_width
or thumbnail_x + thumbnail_width >= self.timeline._history_left:
113 stamp = self.timeline.map_x_to_stamp(thumbnail_x, clamp_to_visible=
False)
115 topic, stamp, max_interval_thumbnail)
118 if not thumbnail_bitmap:
119 thumbnail_details = (thumbnail_height,)
121 (topic, stamp, max_interval_thumbnail, thumbnail_details))
122 if not thumbnail_width:
125 thumbnail_width, _ = thumbnail_bitmap.size
128 if available_width < thumbnail_width:
129 thumbnail_width = available_width - 1
130 QtImage = ImageQt(thumbnail_bitmap)
131 pixmap = QPixmap.fromImage(QtImage)
133 thumbnail_x, thumbnail_y, thumbnail_width, thumbnail_height, pixmap)
134 thumbnail_x += thumbnail_width
139 painter.setPen(QPen(Qt.black))
140 painter.setBrush(QBrush(Qt.transparent))
142 painter.drawRect(x, y, thumbnail_x - x, height - thumbnail_gap - 1)
144 painter.drawRect(x, y, width, height - thumbnail_gap - 1)
154 Loads the thumbnail from the bag
156 (thumbnail_height,) = thumbnail_details
159 t = rospy.Time.from_sec(stamp)
160 bag, entry = self.timeline.scene().get_entry(t, topic)
167 with self.timeline.scene()._bag_lock:
168 msg_topic, msg, msg_stamp = bag._read_message(pos)
172 pil_image = image_helper.imgmsg_to_pil(msg)
173 except Exception
as ex:
174 print(
'Error loading image on topic %s: %s' % (topic, str(ex)), file=sys.stderr)
178 print(
'Disabling renderer on %s' % topic, file=sys.stderr)
179 self.timeline.set_renderer_active(topic,
False)
184 pil_image_size = pil_image.size
185 thumbnail_width = int(
186 round(thumbnail_height * (float(pil_image_size[0]) / pil_image_size[1])))
188 thumbnail = pil_image.resize((thumbnail_width, thumbnail_height), self.
quality)
190 return msg_stamp, thumbnail
192 except Exception
as ex:
193 print(
'Error loading image on topic %s: %s' % (topic, str(ex)), file=sys.stderr)