rxbag: draw active messages
This commit is contained in:
parent
1324c724cd
commit
099b77f9be
|
@ -35,17 +35,22 @@
|
|||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
import rospy
|
||||
import bisect
|
||||
import time
|
||||
|
||||
import wx
|
||||
|
||||
from util.layer import Layer
|
||||
|
||||
## A widget that can render an interval of time of a topic as a rectangle on the timeline
|
||||
class TimelineRenderer:
|
||||
"""
|
||||
A widget that can render an interval of time of a topic as a rectangle on the timeline.
|
||||
@param msg_combine_px: don't draw discrete messages if they're less than this many pixels separated [optional]
|
||||
@type msg_combine_px: float
|
||||
"""
|
||||
def __init__(self, timeline, msg_combine_px=1.5):
|
||||
self.timeline = timeline
|
||||
self.msg_combine_px = msg_combine_px # don't draw discrete messages if they're less than this many pixels separated
|
||||
self.msg_combine_px = msg_combine_px
|
||||
|
||||
def get_segment_height(self, topic):
|
||||
return None
|
||||
|
@ -55,13 +60,13 @@ class TimelineRenderer:
|
|||
|
||||
class MessageView(Layer):
|
||||
"""
|
||||
A widget that can display message details
|
||||
A widget that can display message details.
|
||||
"""
|
||||
|
||||
|
||||
name = 'Untitled'
|
||||
|
||||
def __init__(self, timeline, parent, title, x, y, width, height, max_repaint=None):
|
||||
Layer.__init__(self, parent, title, x, y, width, height, max_repaint)
|
||||
def __init__(self, timeline, parent, title, x, y, width, height):
|
||||
Layer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
self.timeline = timeline
|
||||
self.border = False
|
||||
|
@ -76,55 +81,60 @@ class MessageView(Layer):
|
|||
pass
|
||||
|
||||
class TopicMessageView(MessageView):
|
||||
def __init__(self, timeline, parent, title, x, y, width, height, max_repaint=None):
|
||||
MessageView.__init__(self, timeline, parent, title, x, y, width, height, max_repaint)
|
||||
|
||||
self.topic = None
|
||||
self.msg_index = None
|
||||
|
||||
def __init__(self, timeline, parent, title, x, y, width, height):
|
||||
MessageView.__init__(self, timeline, parent, title, x, y, width, height)
|
||||
|
||||
self.topic = None
|
||||
self.stamp = None
|
||||
self.entry = None
|
||||
|
||||
self._create_toolbar()
|
||||
|
||||
def message_viewed(self, bag, msg_details):
|
||||
topic, msg, t = msg_details
|
||||
|
||||
self.topic = topic
|
||||
#self.msg_index = msg_index
|
||||
|
||||
self.topic = topic
|
||||
self.stamp = t
|
||||
|
||||
def message_cleared(self):
|
||||
pass
|
||||
#self.msg_index = None
|
||||
|
||||
def on_close(self, event):
|
||||
self.timeline.remove_view(self.topic, self)
|
||||
|
||||
def navigate_first(self):
|
||||
# todo: fix
|
||||
if self.topic and self.msg_index is not None:
|
||||
topic_positions = self.timeline.bag_index.msg_positions[self.topic]
|
||||
if len(topic_positions) > 0:
|
||||
self.timeline.set_playhead(topic_positions[0][0])
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
def navigate_previous(self):
|
||||
# todo: fix
|
||||
if self.topic and self.msg_index is not None:
|
||||
new_msg_index = self.msg_index - 1
|
||||
if new_msg_index >= 0:
|
||||
self.timeline.set_playhead(self.timeline.bag_index.msg_positions[self.topic][new_msg_index][0])
|
||||
for entry in self.timeline.bag_file._get_entries(self.timeline.bag_file._get_connections(self.topic)):
|
||||
self.timeline.set_playhead(entry.time.to_sec())
|
||||
break
|
||||
|
||||
def navigate_next(self):
|
||||
# todo: fix
|
||||
if self.topic and self.msg_index is not None:
|
||||
new_msg_index = self.msg_index + 1
|
||||
topic_positions = self.timeline.bag_index.msg_positions[self.topic]
|
||||
if new_msg_index < len(topic_positions):
|
||||
self.timeline.set_playhead(topic_positions[new_msg_index][0])
|
||||
# def navigate_previous(self):
|
||||
# if not self.topic:
|
||||
# return
|
||||
#
|
||||
# index = bisect.bisect_right(self.timeline.message_history_cache[self.topic], self.stamp.to_sec()) - 1
|
||||
# if index > 0:
|
||||
# self.stamp = self.timeline.message_history_cache[self.topic][index - 1]
|
||||
# self.timeline.set_playhead(self.stamp)
|
||||
#
|
||||
# def navigate_next(self):
|
||||
# if not self.topic:
|
||||
# return
|
||||
#
|
||||
# index = bisect.bisect_right(self.timeline.message_history_cache[self.topic], self.stamp.to_sec()) - 1
|
||||
# if index < len(self.timeline.message_history_cache[self.topic]) - 1:
|
||||
# self.stamp = self.timeline.message_history_cache[self.topic][index + 1]
|
||||
# self.timeline.set_playhead(self.stamp)
|
||||
|
||||
def navigate_last(self):
|
||||
# todo: fix
|
||||
if self.topic and self.msg_index is not None:
|
||||
topic_positions = self.timeline.bag_index.msg_positions[self.topic]
|
||||
if len(topic_positions) > 0:
|
||||
self.timeline.set_playhead(topic_positions[-1][0])
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
for entry in self.timeline.bag_file._get_entries_reverse(self.timeline.bag_file._get_connections(self.topic)):
|
||||
self.timeline.set_playhead(entry.time.to_sec())
|
||||
break
|
||||
|
||||
@property
|
||||
def frame(self):
|
||||
|
@ -135,7 +145,7 @@ class TopicMessageView(MessageView):
|
|||
|
||||
tb = self.frame.CreateToolBar()
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_first(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'resultset_first.png')))
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_previous(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'resultset_previous.png')))
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_next(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'resultset_next.png')))
|
||||
#tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_previous(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'resultset_previous.png')))
|
||||
#tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_next(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'resultset_next.png')))
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_last(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'resultset_last.png')))
|
||||
tb.Realize()
|
||||
|
|
|
@ -40,8 +40,8 @@ import wx
|
|||
from util.layer import Layer
|
||||
|
||||
class PlayheadLayer(Layer):
|
||||
def __init__(self, parent, title, timeline, x, y, width, height, max_repaint=None):
|
||||
Layer.__init__(self, parent, title, x, y, width, height, max_repaint)
|
||||
def __init__(self, parent, title, timeline, x, y, width, height):
|
||||
Layer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
self.timeline = timeline
|
||||
|
||||
|
|
|
@ -47,8 +47,8 @@ from message_view import TopicMessageView
|
|||
class RawView(TopicMessageView):
|
||||
name = 'Raw'
|
||||
|
||||
def __init__(self, timeline, parent, title, x, y, width, height, max_repaint=0.1):
|
||||
TopicMessageView.__init__(self, timeline, parent, title, x, y, width, height, max_repaint)
|
||||
def __init__(self, timeline, parent, title, x, y, width, height):
|
||||
TopicMessageView.__init__(self, timeline, parent, title, x, y, width, height)
|
||||
|
||||
self._font = wx.Font(9, wx.FONTFAMILY_MODERN, wx.FONTSTYLE_NORMAL, wx.FONTWEIGHT_NORMAL)
|
||||
|
||||
|
@ -96,6 +96,7 @@ class RawView(TopicMessageView):
|
|||
self.msg_tree.SetSize((size[0], size[1] - self.msg_tree.GetPosition()[1]))
|
||||
|
||||
def clear(self):
|
||||
self.msg_title.SetValue('')
|
||||
self.msg_incoming = None
|
||||
self.invalidate()
|
||||
|
||||
|
|
|
@ -87,8 +87,8 @@ class RxBagApp(wx.App):
|
|||
frame.Bind(wx.EVT_CLOSE, lambda e: wx.Exit())
|
||||
|
||||
except Exception, ex:
|
||||
rospy.logerr('Error initializing application: %s' % str(ex))
|
||||
raise
|
||||
print >> sys.stderr, 'Error initializing application:', ex
|
||||
return False
|
||||
|
||||
return True
|
||||
|
||||
|
|
|
@ -41,8 +41,8 @@ from util.layer import Layer
|
|||
from bag_helper import BagHelper
|
||||
|
||||
class StatusLayer(Layer):
|
||||
def __init__(self, parent, title, timeline, x, y, width, height, max_repaint=None):
|
||||
Layer.__init__(self, parent, title, x, y, width, height, max_repaint)
|
||||
def __init__(self, parent, title, timeline, x, y, width, height):
|
||||
Layer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
self.timeline = timeline
|
||||
|
||||
|
|
|
@ -92,7 +92,7 @@ class TimelinePanel(LayerPanel):
|
|||
|
||||
x, y = 5, 19
|
||||
|
||||
self.timeline = Timeline(self, 'Timeline', x, y, width - x, height - y, max_repaint=1.0)
|
||||
self.timeline = Timeline(self, 'Timeline', x, y, width - x, height - y)
|
||||
self.timeline.set_bag_files(self.bag_files)
|
||||
|
||||
self.status = status.StatusLayer(self, 'Status', self.timeline, self.timeline.x, 4, 300, 16)
|
||||
|
@ -142,8 +142,8 @@ class TimelinePanel(LayerPanel):
|
|||
class Timeline(Layer):
|
||||
name = 'Timeline'
|
||||
|
||||
def __init__(self, parent, title, x, y, width, height, max_repaint=None):
|
||||
Layer.__init__(self, parent, title, x, y, width, height, max_repaint)
|
||||
def __init__(self, parent, title, x, y, width, height):
|
||||
Layer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
self.bag_files = {}
|
||||
self.bag_file = None
|
||||
|
@ -390,6 +390,7 @@ class Timeline(Layer):
|
|||
self.listeners.setdefault(topic, []).append(listener)
|
||||
|
||||
self.update_message_view()
|
||||
self.invalidate()
|
||||
|
||||
def remove_listener(self, topic, listener):
|
||||
topic_listeners = self.listeners.get(topic)
|
||||
|
@ -397,6 +398,7 @@ class Timeline(Layer):
|
|||
topic_listeners.remove(listener)
|
||||
if len(topic_listeners) == 0:
|
||||
del self.listeners[topic]
|
||||
self.invalidate()
|
||||
|
||||
@property
|
||||
def history_bottom(self):
|
||||
|
@ -604,7 +606,9 @@ class Timeline(Layer):
|
|||
row += 1
|
||||
|
||||
def _draw_time_indicators(self, dc):
|
||||
"""Draw time indicators on the timeline"""
|
||||
"""
|
||||
Draw vertical grid-lines showing major and minor time divisions.
|
||||
"""
|
||||
|
||||
x_per_sec = self.map_dstamp_to_dx(1.0)
|
||||
|
||||
|
@ -632,7 +636,7 @@ class Timeline(Layer):
|
|||
dc.set_line_width(1)
|
||||
|
||||
for stamp in stamps:
|
||||
x = self.map_stamp_to_x(stamp, False)
|
||||
x = self.map_stamp_to_x(stamp, False)
|
||||
|
||||
label = self._get_label(division, stamp - start_stamp)
|
||||
label_x = x + 3
|
||||
|
@ -646,9 +650,9 @@ class Timeline(Layer):
|
|||
dc.set_source_rgba(0.25, 0.25, 0.25, 0.3)
|
||||
dc.move_to(x, label_y + 1)
|
||||
dc.line_to(x, self.history_bottom)
|
||||
|
||||
dc.stroke()
|
||||
|
||||
dc.stroke()
|
||||
|
||||
def _draw_minor_divisions(self, dc, stamps, start_stamp, division):
|
||||
xs = [self.map_stamp_to_x(stamp) for stamp in stamps]
|
||||
|
||||
|
@ -708,7 +712,7 @@ class Timeline(Layer):
|
|||
break
|
||||
else:
|
||||
self._draw_topic_history(dc, topic)
|
||||
|
||||
|
||||
def _draw_topic_history(self, dc, topic):
|
||||
"""
|
||||
Draw boxes to show message regions on timelines.
|
||||
|
@ -733,9 +737,6 @@ class Timeline(Layer):
|
|||
if msg_combine_interval is None:
|
||||
msg_combine_interval = self.map_dx_to_dstamp(self.default_msg_combine_px)
|
||||
|
||||
start_time = roslib.rostime.Time.from_sec(max(0.0, self.stamp_left))
|
||||
end_time = roslib.rostime.Time.from_sec(max(0.0, self.stamp_right))
|
||||
|
||||
if topic not in self.message_history_cache:
|
||||
start_time = roslib.rostime.Time.from_sec(max(0.0, self.start_stamp))
|
||||
end_time = roslib.rostime.Time.from_sec(max(0.0, self.end_stamp))
|
||||
|
@ -744,17 +745,19 @@ class Timeline(Layer):
|
|||
self.message_history_cache[topic] = all_stamps
|
||||
else:
|
||||
all_stamps = self.message_history_cache[topic]
|
||||
|
||||
|
||||
start_index = bisect.bisect_left(all_stamps, self.stamp_left)
|
||||
end_index = bisect.bisect_left(all_stamps, self.stamp_right)
|
||||
|
||||
# Set pen based on datatype
|
||||
datatype_color = self.datatype_colors.get(datatype, self.default_datatype_color)
|
||||
dc.set_source_rgb(datatype_color.red / 255.0, datatype_color.green / 255.0, datatype_color.blue / 255.0)
|
||||
datatype_rgb = datatype_color.red / 255.0, datatype_color.green / 255.0, datatype_color.blue / 255.0
|
||||
|
||||
# Iterate through regions of connected messages
|
||||
width_interval = self.history_width / (self.stamp_right - self.stamp_left)
|
||||
|
||||
dc.set_line_width(1)
|
||||
dc.set_source_rgb(*datatype_rgb)
|
||||
for (stamp_start, stamp_end) in self._find_regions(all_stamps[start_index:end_index], self.map_dx_to_dstamp(self.default_msg_combine_px)):
|
||||
region_x_start = self.history_left + (stamp_start - self.stamp_left) * width_interval
|
||||
region_x_end = self.history_left + (stamp_end - self.stamp_left) * width_interval
|
||||
|
@ -764,6 +767,19 @@ class Timeline(Layer):
|
|||
|
||||
dc.fill()
|
||||
|
||||
# Draw active message
|
||||
if topic in self.listeners:
|
||||
dc.set_line_width(3)
|
||||
playhead_stamp = None
|
||||
playhead_index = bisect.bisect_right(all_stamps, self.playhead) - 1
|
||||
if playhead_index >= 0:
|
||||
playhead_stamp = all_stamps[playhead_index]
|
||||
if playhead_stamp > self.stamp_left and playhead_stamp < self.stamp_right:
|
||||
playhead_x = self.history_left + (all_stamps[playhead_index] - self.stamp_left) * width_interval
|
||||
dc.move_to(playhead_x, msg_y)
|
||||
dc.line_to(playhead_x, msg_y + msg_height)
|
||||
dc.stroke()
|
||||
|
||||
# Custom renderer
|
||||
if renderer:
|
||||
# Iterate through regions of connected messages
|
||||
|
@ -956,11 +972,12 @@ class Timeline(Layer):
|
|||
msgs[topic] = None
|
||||
|
||||
# Inform the listeners
|
||||
for topic, msg_data in msgs.items():
|
||||
for topic in self.topics:
|
||||
topic_listeners = self.listeners.get(topic)
|
||||
if not topic_listeners:
|
||||
continue
|
||||
|
||||
msg_data = msgs.get(topic)
|
||||
if msg_data:
|
||||
for listener in topic_listeners:
|
||||
listener.message_viewed(self.bag_file, msg_data)
|
||||
|
|
|
@ -40,7 +40,7 @@ import wx.lib.wxcairo
|
|||
class Layer:
|
||||
name = 'Untitled'
|
||||
|
||||
def __init__(self, parent, title, x, y, width, height, max_repaint=None):
|
||||
def __init__(self, parent, title, x, y, width, height):
|
||||
self._x = x
|
||||
self._y = y
|
||||
self._width = width
|
||||
|
|
Loading…
Reference in New Issue