image_timeline_renderer.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2009, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 from __future__ import print_function
34 import rospy
35 
36 # HACK workaround for upstream pillow issue python-pillow/Pillow#400
37 import sys
38 from python_qt_binding import QT_BINDING_MODULES
39 if (
40  not QT_BINDING_MODULES['QtCore'].__name__.startswith('PyQt5') and
41  'PyQt5' in sys.modules
42 ):
43  sys.modules['PyQt5'] = None
44 from PIL import Image
45 from PIL.ImageQt import ImageQt
46 
47 from rqt_bag import TimelineCache, TimelineRenderer
48 
49 from rqt_bag_plugins import image_helper
50 
51 from python_qt_binding.QtCore import Qt
52 from python_qt_binding.QtGui import QBrush, QPen, QPixmap
53 
54 
55 class ImageTimelineRenderer(TimelineRenderer):
56 
57  """
58  Draws thumbnails of sensor_msgs/Image or sensor_msgs/CompressedImage in the timeline.
59  """
60 
61  def __init__(self, timeline, thumbnail_height=160):
62  super(ImageTimelineRenderer, self).__init__(timeline, msg_combine_px=40.0)
63 
64  self.thumbnail_height = thumbnail_height
65 
66  self.thumbnail_combine_px = 20.0 # use cached thumbnail if it's less than this many pixels away
67  self.min_thumbnail_width = 8 # don't display thumbnails if less than this many pixels across
68  self.quality = Image.NEAREST # quality hint for thumbnail scaling
69 
70  self.thumbnail_cache = TimelineCache(
71  self._load_thumbnail, lambda topic, msg_stamp, thumbnail: self.timeline.scene().update())
72  # TimelineRenderer implementation
73 
74  def get_segment_height(self, topic):
75  return self.thumbnail_height
76 
77  def draw_timeline_segment(self, painter, topic, stamp_start, stamp_end, x, y, width, height):
78  """
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''
88  """
89  if x < self.timeline._history_left:
90  width += x - self.timeline._history_left
91  x = self.timeline._history_left
92  max_interval_thumbnail = self.timeline.map_dx_to_dstamp(self.thumbnail_combine_px)
93  max_interval_thumbnail = max(0.1, max_interval_thumbnail)
94  thumbnail_gap = 6
95  # leave 1px border
96  thumbnail_x, thumbnail_y, thumbnail_height = x + 1, y + 1, height - 2 - thumbnail_gap
97 
98  # set color to white draw rectangle over messages
99  painter.setBrush(QBrush(Qt.white))
100  painter.drawRect(x, y, width, height - thumbnail_gap)
101  thumbnail_width = None
102 
103  while True:
104  available_width = (x + width) - thumbnail_x
105 
106  # Check for enough remaining to draw thumbnail
107  if width > 1 and available_width < self.min_thumbnail_width:
108  break
109 
110  # Try to display the thumbnail, if its right edge is to the right of the
111  # timeline's left side
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)
114  thumbnail_bitmap = self.thumbnail_cache.get_item(
115  topic, stamp, max_interval_thumbnail)
116 
117  # Cache miss
118  if not thumbnail_bitmap:
119  thumbnail_details = (thumbnail_height,)
120  self.thumbnail_cache.enqueue(
121  (topic, stamp, max_interval_thumbnail, thumbnail_details))
122  if not thumbnail_width:
123  break
124  else:
125  thumbnail_width, _ = thumbnail_bitmap.size
126 
127  if width > 1:
128  if available_width < thumbnail_width:
129  thumbnail_width = available_width - 1
130  QtImage = ImageQt(thumbnail_bitmap)
131  pixmap = QPixmap.fromImage(QtImage)
132  painter.drawPixmap(
133  thumbnail_x, thumbnail_y, thumbnail_width, thumbnail_height, pixmap)
134  thumbnail_x += thumbnail_width
135 
136  if width == 1:
137  break
138 
139  painter.setPen(QPen(Qt.black))
140  painter.setBrush(QBrush(Qt.transparent))
141  if width == 1:
142  painter.drawRect(x, y, thumbnail_x - x, height - thumbnail_gap - 1)
143  else:
144  painter.drawRect(x, y, width, height - thumbnail_gap - 1)
145  return True
146 
147  def close(self):
148  if self.thumbnail_cache:
149  self.thumbnail_cache.stop()
150  self.thumbnail_cache.join()
151 
152  def _load_thumbnail(self, topic, stamp, thumbnail_details):
153  """
154  Loads the thumbnail from the bag
155  """
156  (thumbnail_height,) = thumbnail_details
157 
158  # Find position of stamp using index
159  t = rospy.Time.from_sec(stamp)
160  bag, entry = self.timeline.scene().get_entry(t, topic)
161  if not entry:
162  return None, None
163  pos = entry.position
164 
165  # Not in the cache; load from the bag file
166 
167  with self.timeline.scene()._bag_lock:
168  msg_topic, msg, msg_stamp = bag._read_message(pos)
169 
170  # Convert from ROS image to PIL image
171  try:
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)
175  pil_image = None
176 
177  if not pil_image:
178  print('Disabling renderer on %s' % topic, file=sys.stderr)
179  self.timeline.set_renderer_active(topic, False)
180  return None, None
181 
182  # Calculate width to maintain aspect ratio
183  try:
184  pil_image_size = pil_image.size
185  thumbnail_width = int(
186  round(thumbnail_height * (float(pil_image_size[0]) / pil_image_size[1])))
187  # Scale to thumbnail size
188  thumbnail = pil_image.resize((thumbnail_width, thumbnail_height), self.quality)
189 
190  return msg_stamp, thumbnail
191 
192  except Exception as ex:
193  print('Error loading image on topic %s: %s' % (topic, str(ex)), file=sys.stderr)
194  raise
195  return None, None
def draw_timeline_segment(self, painter, topic, stamp_start, stamp_end, x, y, width, height)


rqt_bag_plugins
Author(s): Dirk Thomas , Aaron Blasdel , Austin Hendrix , Tim Field
autogenerated on Fri Feb 19 2021 03:14:15