rxbag: tidying up
This commit is contained in:
parent
08c4cad5a1
commit
4e0e7c9ca9
|
@ -34,6 +34,7 @@
|
|||
from rxbag_main import rxbag_main
|
||||
|
||||
import bag_helper
|
||||
from plugin.message_view import MessageView, TopicMessageView
|
||||
from plugin.timeline_renderer import TimelineRenderer
|
||||
from timeline_cache import TimelineCache
|
||||
from plugin.message_view import MessageView
|
||||
from plugin.topic_message_view import TopicMessageView
|
||||
from plugin.timeline_renderer import TimelineRenderer
|
||||
from timeline_cache import TimelineCache
|
||||
|
|
|
@ -49,7 +49,7 @@ def stamp_to_str(t):
|
|||
@type t: rospy.Time
|
||||
"""
|
||||
t_sec = t.to_sec()
|
||||
if t < rospy.Time.from_sec(60 * 60 * 24 * 7 * 52 * 5):
|
||||
if t < rospy.Time.from_sec(60 * 60 * 24 * 365 * 5):
|
||||
# Display timestamps earlier than 1975 as seconds
|
||||
return '%.3fs' % t_sec
|
||||
else:
|
||||
|
|
|
@ -37,10 +37,6 @@ Player listens to messages from the timeline and publishes them to ROS.
|
|||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import sys
|
||||
import threading
|
||||
import time
|
||||
|
||||
import wx
|
||||
|
||||
import rosbag
|
||||
|
|
|
@ -1,105 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2009, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
"""
|
||||
Draws the playhead indicator on the timeline.
|
||||
"""
|
||||
|
||||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import wx
|
||||
|
||||
from util.layer import TransparentLayer
|
||||
|
||||
class PlayheadLayer(TransparentLayer):
|
||||
def __init__(self, parent, title, timeline, x, y, width, height):
|
||||
TransparentLayer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
self.timeline = timeline
|
||||
|
||||
self.pointer_size = (6, 6)
|
||||
|
||||
self.timeline_rect = self._get_timeline_rect()
|
||||
|
||||
def check_dirty(self):
|
||||
timeline_rect = self._get_timeline_rect()
|
||||
if self.timeline_rect != timeline_rect:
|
||||
self.timeline_rect = timeline_rect
|
||||
self.update_position()
|
||||
|
||||
def paint(self, dc):
|
||||
TransparentLayer.paint(self, dc)
|
||||
|
||||
if not self.timeline.playhead:
|
||||
return
|
||||
|
||||
px, pw, ph = self.width / 2, self.pointer_size[0], self.pointer_size[1]
|
||||
|
||||
# Line
|
||||
dc.set_line_width(2)
|
||||
dc.set_source_rgba(1, 0, 0, 0.75)
|
||||
dc.move_to(px, self.timeline.history_top - 1)
|
||||
dc.line_to(px, self.timeline.history_bottom + 2)
|
||||
dc.stroke()
|
||||
|
||||
dc.set_source_rgb(1, 0, 0)
|
||||
|
||||
# Upper triangle
|
||||
py = self.timeline.history_top - ph
|
||||
dc.move_to(px, py + ph)
|
||||
dc.line_to(px + pw, py)
|
||||
dc.line_to(px - pw, py)
|
||||
dc.line_to(px , py + ph)
|
||||
dc.fill()
|
||||
|
||||
# Lower triangle
|
||||
py = self.timeline.history_bottom + 1
|
||||
dc.move_to(px, py)
|
||||
dc.line_to(px + pw, py + ph)
|
||||
dc.line_to(px - pw, py + ph)
|
||||
dc.line_to(px, py)
|
||||
dc.fill()
|
||||
|
||||
def on_size(self, event):
|
||||
self.resize(self.width, self.timeline.height)
|
||||
|
||||
def update_position(self):
|
||||
if not self.timeline.playhead:
|
||||
return
|
||||
|
||||
playhead_x = self.timeline.map_stamp_to_x(self.timeline.playhead.to_sec())
|
||||
|
||||
self.move(self.timeline.x + playhead_x - self.width / 2, self.timeline.y)
|
||||
|
||||
def _get_timeline_rect(self):
|
||||
return (self.timeline.history_left, self.timeline.history_top, self.timeline.history_width, self.timeline.history_height)
|
|
@ -32,27 +32,16 @@
|
|||
|
||||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
import rospy
|
||||
|
||||
import bisect
|
||||
import time
|
||||
|
||||
import wx
|
||||
|
||||
from rxbag.util.layer import Layer
|
||||
|
||||
class MessageView(Layer):
|
||||
class MessageView(object):
|
||||
"""
|
||||
A message details renderer. When registered with rxbag, a MessageView is called
|
||||
whenever the timeline playhead moves.
|
||||
"""
|
||||
name = 'Untitled'
|
||||
|
||||
def __init__(self, timeline, parent, title, x, y, width, height):
|
||||
Layer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
def __init__(self, timeline):
|
||||
self.timeline = timeline
|
||||
self.border = False
|
||||
|
||||
def message_viewed(self, bag, topic, msg, t):
|
||||
"""
|
||||
|
@ -87,76 +76,3 @@ class MessageView(Layer):
|
|||
Close the message view, releasing any resources.
|
||||
"""
|
||||
pass
|
||||
|
||||
class TopicMessageView(MessageView):
|
||||
"""
|
||||
A message view with a toolbar for navigating messages.
|
||||
"""
|
||||
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):
|
||||
self.topic, _, self.stamp = msg_details
|
||||
|
||||
def on_close(self, event):
|
||||
self.timeline.remove_view(self.topic, self)
|
||||
|
||||
def navigate_first(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
for entry in self.timeline.get_entries(self.topic, self.timeline.start_stamp, self.timeline.end_stamp):
|
||||
self.timeline.playhead = entry.time
|
||||
break
|
||||
|
||||
def navigate_previous(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
last_entry = None
|
||||
for entry in self.timeline.get_entries(self.topic, self.timeline.start_stamp, self.timeline.playhead):
|
||||
if entry.time < self.timeline.playhead:
|
||||
last_entry = entry
|
||||
|
||||
if last_entry:
|
||||
self.timeline.playhead = last_entry.time
|
||||
|
||||
def navigate_next(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
for entry in self.timeline.get_entries(self.topic, self.timeline.playhead, self.timeline.end_stamp):
|
||||
if entry.time > self.timeline.playhead:
|
||||
self.timeline.playhead = entry.time
|
||||
break
|
||||
|
||||
def navigate_last(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
last_entry = None
|
||||
for entry in self.timeline.get_entries(self.topic, self.timeline.start_stamp, self.timeline.end_stamp):
|
||||
last_entry = entry
|
||||
|
||||
if last_entry:
|
||||
self.timeline.playhead = last_entry.time
|
||||
|
||||
@property
|
||||
def frame(self):
|
||||
return self.parent.GetParent()
|
||||
|
||||
def _create_toolbar(self):
|
||||
icons_dir = roslib.packages.get_pkg_dir(PKG) + '/icons/'
|
||||
|
||||
tb = self.frame.CreateToolBar()
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_first(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_first.png')))
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_previous(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_previous.png')))
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_next(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_next.png')))
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.navigate_last(), tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_last.png')))
|
||||
tb.Realize()
|
||||
|
|
|
@ -32,14 +32,6 @@
|
|||
|
||||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
import rospy
|
||||
|
||||
import bisect
|
||||
import time
|
||||
|
||||
import wx
|
||||
|
||||
from rxbag.util.layer import Layer
|
||||
|
||||
class TimelineRenderer(object):
|
||||
"""
|
||||
|
@ -67,7 +59,7 @@ class TimelineRenderer(object):
|
|||
"""
|
||||
Draw the timeline segment.
|
||||
|
||||
@param dc: Cairo device context to render into
|
||||
@param dc: Cairo context to render into
|
||||
@param topic: topic name
|
||||
@param stamp_start: start of the interval on the timeline
|
||||
@param stamp_end: start of the interval on the timeline
|
||||
|
|
|
@ -0,0 +1,177 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2009, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import wx
|
||||
|
||||
from rxbag import bag_helper
|
||||
from message_view import MessageView
|
||||
|
||||
class TopicMessageView(MessageView):
|
||||
"""
|
||||
A message view with a toolbar for navigating messages in a single topic.
|
||||
"""
|
||||
def __init__(self, timeline, parent):
|
||||
MessageView.__init__(self, timeline)
|
||||
|
||||
self._parent = parent
|
||||
self._topic = None
|
||||
self._stamp = None
|
||||
|
||||
self._toolbar = self.parent.CreateToolBar()
|
||||
self._setup_toolbar()
|
||||
|
||||
self.parent.StatusBar = TopicMessageViewStatusBar(self.parent, self)
|
||||
|
||||
self.parent.Bind(wx.EVT_CLOSE, self._on_close)
|
||||
|
||||
@property
|
||||
def parent(self): return self._parent
|
||||
|
||||
@property
|
||||
def topic(self): return self._topic
|
||||
|
||||
@property
|
||||
def stamp(self): return self._stamp
|
||||
|
||||
## MessageView implementation
|
||||
|
||||
def message_viewed(self, bag, msg_details):
|
||||
self._topic, _, self._stamp = msg_details[:3]
|
||||
|
||||
wx.CallAfter(self.parent.StatusBar.update)
|
||||
|
||||
## Events
|
||||
|
||||
def _on_close(self, event):
|
||||
# @todo: needs to handle closing when a message hasn't been viewed yet
|
||||
if self._topic:
|
||||
self.timeline.remove_view(self._topic, self)
|
||||
|
||||
event.Skip()
|
||||
|
||||
def navigate_first(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
for entry in self.timeline.get_entries(self._topic, self.timeline.start_stamp, self.timeline.end_stamp):
|
||||
self.timeline.playhead = entry.time
|
||||
break
|
||||
|
||||
def navigate_previous(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
last_entry = None
|
||||
for entry in self.timeline.get_entries(self._topic, self.timeline.start_stamp, self.timeline.playhead):
|
||||
if entry.time < self.timeline.playhead:
|
||||
last_entry = entry
|
||||
|
||||
if last_entry:
|
||||
self.timeline.playhead = last_entry.time
|
||||
|
||||
def navigate_next(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
for entry in self.timeline.get_entries(self._topic, self.timeline.playhead, self.timeline.end_stamp):
|
||||
if entry.time > self.timeline.playhead:
|
||||
self.timeline.playhead = entry.time
|
||||
break
|
||||
|
||||
def navigate_last(self):
|
||||
if not self.topic:
|
||||
return
|
||||
|
||||
last_entry = None
|
||||
for entry in self.timeline.get_entries(self._topic, self.timeline.start_stamp, self.timeline.end_stamp):
|
||||
last_entry = entry
|
||||
|
||||
if last_entry:
|
||||
self.timeline.playhead = last_entry.time
|
||||
|
||||
def _setup_toolbar(self):
|
||||
self._toolbar.ClearTools()
|
||||
|
||||
icons_dir = roslib.packages.get_pkg_dir(PKG) + '/icons/'
|
||||
|
||||
navigate_first_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_first.png'))
|
||||
navigate_previous_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_previous.png'))
|
||||
navigate_next_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_next.png'))
|
||||
navigate_last_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_last.png'))
|
||||
|
||||
self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_first(), navigate_first_tool)
|
||||
self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_previous(), navigate_previous_tool)
|
||||
self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_next(), navigate_next_tool)
|
||||
self._toolbar.Bind(wx.EVT_TOOL, lambda e: self.navigate_last(), navigate_last_tool)
|
||||
|
||||
self._toolbar.Realize()
|
||||
|
||||
class TopicMessageViewStatusBar(wx.StatusBar):
|
||||
def __init__(self, parent, message_view):
|
||||
wx.StatusBar.__init__(self, parent, -1)
|
||||
|
||||
self.message_view = message_view
|
||||
|
||||
self.timestamp_field = 1
|
||||
self.human_readable_field = 2
|
||||
self.elapsed_field = 3
|
||||
|
||||
self.timestamp_width = 125
|
||||
self.human_readable_width = 180
|
||||
self.elapsed_width = 110
|
||||
|
||||
self.SetFieldsCount(4)
|
||||
|
||||
parent.Bind(wx.EVT_SIZE, self.on_size)
|
||||
|
||||
self.update()
|
||||
|
||||
def on_size(self, event):
|
||||
main_width = max(10, self.Size[0] - (self.timestamp_width + self.human_readable_width + self.elapsed_width))
|
||||
self.SetStatusWidths([main_width, self.timestamp_width, self.human_readable_width, self.elapsed_width])
|
||||
event.Skip()
|
||||
|
||||
def update(self):
|
||||
if self.message_view.stamp is None or self.message_view.timeline.start_stamp is None:
|
||||
return
|
||||
|
||||
# Raw timestamp
|
||||
self.SetStatusText('%d.%s' % (self.message_view.stamp.secs, str(self.message_view.stamp.nsecs)[:3]), self.timestamp_field)
|
||||
|
||||
# Human-readable time
|
||||
self.SetStatusText(bag_helper.stamp_to_str(self.message_view.stamp), self.human_readable_field)
|
||||
|
||||
# Elapsed time (in seconds)
|
||||
self.SetStatusText('%.3fs' % (self.message_view.stamp - self.message_view.timeline.start_stamp).to_sec(), self.elapsed_field)
|
|
@ -37,7 +37,6 @@ Loads plugins.
|
|||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import os
|
||||
import sys
|
||||
import traceback
|
||||
|
||||
|
|
|
@ -37,37 +37,32 @@ Defines a raw view: a TopicMessageView that displays the message contents in a t
|
|||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import rospy
|
||||
|
||||
import codecs
|
||||
import math
|
||||
import sys
|
||||
import time
|
||||
|
||||
import wx
|
||||
|
||||
import rospy
|
||||
|
||||
import bag_helper
|
||||
from plugin.message_view import TopicMessageView
|
||||
from plugin.topic_message_view import TopicMessageView
|
||||
|
||||
class RawView(TopicMessageView):
|
||||
name = 'Raw'
|
||||
|
||||
def __init__(self, timeline, parent, title, x, y, width, height):
|
||||
TopicMessageView.__init__(self, timeline, parent, title, x, y, width, height)
|
||||
def __init__(self, timeline, parent):
|
||||
TopicMessageView.__init__(self, timeline, parent)
|
||||
|
||||
self._font = wx.Font(9, wx.FONTFAMILY_MODERN, wx.FONTSTYLE_NORMAL, wx.FONTWEIGHT_NORMAL)
|
||||
|
||||
self.msg_title = wx.TextCtrl(self.parent, style=wx.TE_READONLY | wx.NO_BORDER)
|
||||
self.msg_title.SetPosition((1, 0))
|
||||
self.msg_title.SetFont(self._font)
|
||||
|
||||
self.msg_tree = MessageTree(self.parent)
|
||||
self.msg_tree.SetPosition((0, 20))
|
||||
#self.msg_tree.Position = (0, 0)
|
||||
|
||||
self.msg_displayed = None
|
||||
self.msg_incoming = None
|
||||
|
||||
self.parent.Bind(wx.EVT_PAINT, self.on_paint)
|
||||
self.parent.Bind(wx.EVT_SIZE, self.on_size)
|
||||
|
||||
#self.self_paint = True
|
||||
## MessageView implementation
|
||||
|
||||
def message_viewed(self, bag, msg_details):
|
||||
TopicMessageView.message_viewed(self, bag, msg_details)
|
||||
|
@ -77,38 +72,29 @@ class RawView(TopicMessageView):
|
|||
if t is None:
|
||||
self.message_cleared()
|
||||
else:
|
||||
time_str = '%s (%10d.%09d) [%.3fs]' % (bag_helper.stamp_to_str(t), t.secs, t.nsecs, (t - self.timeline.start_stamp).to_sec())
|
||||
|
||||
if len(self.timeline.bags) > 1:
|
||||
self.msg_title.SetValue('%s (%s)' % (time_str, bag.filename))
|
||||
else:
|
||||
self.msg_title.SetValue(time_str)
|
||||
self.msg_title.Refresh()
|
||||
|
||||
self.msg_incoming = msg
|
||||
self.invalidate()
|
||||
wx.CallAfter(self.parent.Refresh)
|
||||
|
||||
def message_cleared(self):
|
||||
TopicMessageView.message_cleared(self)
|
||||
|
||||
self.clear()
|
||||
|
||||
def paint(self, dc):
|
||||
## Events
|
||||
|
||||
def on_paint(self, dc):
|
||||
if self.msg_incoming != self.msg_displayed:
|
||||
self.msg_tree.set_message(self.msg_incoming)
|
||||
self.msg_displayed = self.msg_incoming
|
||||
|
||||
def on_size(self, event):
|
||||
size = self.parent.GetClientSize()
|
||||
|
||||
self.resize(*size)
|
||||
self.msg_title.SetSize((size[0], 20))
|
||||
self.msg_tree.SetSize((size[0], size[1] - self.msg_tree.GetPosition()[1]))
|
||||
self.msg_tree.Size = self.parent.ClientSize
|
||||
|
||||
##
|
||||
|
||||
def clear(self):
|
||||
self.msg_title.SetValue('')
|
||||
self.msg_incoming = None
|
||||
self.invalidate()
|
||||
wx.CallAfter(self.parent.Refresh)
|
||||
|
||||
class MessageTree(wx.TreeCtrl):
|
||||
def __init__(self, parent):
|
||||
|
@ -163,7 +149,7 @@ class MessageTree(wx.TreeCtrl):
|
|||
self.Refresh()
|
||||
|
||||
def on_key_up(self, event):
|
||||
key, ctrl = event.GetKeyCode(), event.ControlDown()
|
||||
key, ctrl = event.KeyCode, event.ControlDown()
|
||||
|
||||
if ctrl:
|
||||
if key == ord('C') or key == ord('c'):
|
||||
|
@ -207,7 +193,7 @@ class MessageTree(wx.TreeCtrl):
|
|||
|
||||
def get_all_items(self):
|
||||
items = []
|
||||
self.traverse(self.GetRootItem(), items.append)
|
||||
self.traverse(self.RootItem, items.append)
|
||||
return items
|
||||
|
||||
def traverse(self, root, function):
|
||||
|
@ -247,7 +233,7 @@ class MessageTree(wx.TreeCtrl):
|
|||
else:
|
||||
label += ': %s' % obj_repr
|
||||
|
||||
elif type(obj) in [str, bool, int, long, float, complex, roslib.rostime.Time]:
|
||||
elif type(obj) in [str, bool, int, long, float, complex, rospy.Time]:
|
||||
# Ignore any binary data
|
||||
obj_repr = codecs.utf_8_decode(str(obj), 'ignore')[0]
|
||||
|
||||
|
|
|
@ -49,7 +49,7 @@ import wx
|
|||
import rosbag
|
||||
|
||||
import util.base_frame
|
||||
import timeline_panel
|
||||
from timeline import Timeline
|
||||
|
||||
class RxBagApp(wx.App):
|
||||
def __init__(self, options, args):
|
||||
|
@ -81,23 +81,24 @@ class RxBagApp(wx.App):
|
|||
|
||||
# Create main timeline frame
|
||||
self.frame = util.base_frame.BaseFrame(None, 'rxbag', 'Timeline')
|
||||
self.frame.SetBackgroundColour(wx.WHITE)
|
||||
self.frame.BackgroundColour = wx.WHITE
|
||||
self.frame.Bind(wx.EVT_CLOSE, lambda e: wx.Exit())
|
||||
|
||||
scroll = wx.ScrolledWindow(self.frame, -1)
|
||||
scroll.SetBackgroundColour(wx.WHITE)
|
||||
scroll.BackgroundColour = wx.WHITE
|
||||
|
||||
panel = timeline_panel.TimelinePanel(scroll, -1)
|
||||
panel.create_controls()
|
||||
panel.SetSize((100, 100))
|
||||
timeline = Timeline(scroll, -1)
|
||||
timeline.Size = (100, 100)
|
||||
|
||||
self.frame.Show()
|
||||
self.SetTopWindow(self.frame)
|
||||
|
||||
timeline.SetFocus()
|
||||
|
||||
if self.options.record:
|
||||
panel.timeline.record_bag(record_filename, all=self.options.all, topics=self.args, regex=self.options.regex, limit=self.options.limit)
|
||||
timeline.record_bag(record_filename, all=self.options.all, topics=self.args, regex=self.options.regex, limit=self.options.limit)
|
||||
else:
|
||||
RxBagInitThread(self, panel.timeline)
|
||||
RxBagInitThread(self, timeline)
|
||||
|
||||
except Exception, ex:
|
||||
print >> sys.stderr, 'Error initializing application:', ex
|
||||
|
|
File diff suppressed because it is too large
Load Diff
125
tools/rxbag/src/rxbag/timeline_panel.py → tools/rxbag/src/rxbag/timeline_popup_menu.py
Executable file → Normal file
125
tools/rxbag/src/rxbag/timeline_panel.py → tools/rxbag/src/rxbag/timeline_popup_menu.py
Executable file → Normal file
|
@ -30,112 +30,21 @@
|
|||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
"""
|
||||
The containing window for the timeline control. Defines the toolbar and menus.
|
||||
"""
|
||||
|
||||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import wx
|
||||
|
||||
from playhead import PlayheadLayer
|
||||
from status import StatusLayer
|
||||
from timeline import Timeline
|
||||
from util.base_frame import BaseFrame
|
||||
from util.layer import LayerPanel
|
||||
|
||||
class TimelinePanel(LayerPanel):
|
||||
def __init__(self, *args, **kwargs):
|
||||
LayerPanel.__init__(self, *args, **kwargs)
|
||||
|
||||
def create_controls(self):
|
||||
(width, height) = wx.GetApp().GetTopWindow().GetClientSize()
|
||||
self.timeline = Timeline (self, 'Timeline', 5, 19, width - 5, height - 19)
|
||||
self.status = StatusLayer (self, 'Status', self.timeline, self.timeline.x, 4, 300, 16)
|
||||
self.playhead = PlayheadLayer(self, 'Playhead', self.timeline, 0, 0, 12, self.timeline.height)
|
||||
self.layers = [self.timeline, self.status, self.playhead]
|
||||
|
||||
self.setup_toolbar()
|
||||
self.update_title()
|
||||
|
||||
def update_title(self):
|
||||
wx.GetApp().GetTopWindow().SetTitle(self.timeline.get_title())
|
||||
|
||||
def setup_toolbar(self):
|
||||
tb = wx.GetApp().GetTopWindow().GetToolBar()
|
||||
if tb:
|
||||
tb.ClearTools()
|
||||
else:
|
||||
tb = wx.GetApp().GetTopWindow().CreateToolBar()
|
||||
|
||||
icons_dir = roslib.packages.get_pkg_dir(PKG) + '/icons/'
|
||||
|
||||
start_icon = wx.Bitmap(icons_dir + 'start.png')
|
||||
rewind_icon = wx.Bitmap(icons_dir + 'rewind.png')
|
||||
play_icon = wx.Bitmap(icons_dir + 'play.png')
|
||||
fastforward_icon = wx.Bitmap(icons_dir + 'fastforward.png')
|
||||
end_icon = wx.Bitmap(icons_dir + 'end.png')
|
||||
stop_icon = wx.Bitmap(icons_dir + 'stop.png')
|
||||
|
||||
if self.timeline._play_speed > 1.0:
|
||||
fastforward_icon = wx.Bitmap(icons_dir + 'fastforward_active.png')
|
||||
elif self.timeline._play_speed > 0.0:
|
||||
play_icon = wx.Bitmap(icons_dir + 'play_active.png')
|
||||
elif self.timeline._play_speed == 0.0:
|
||||
stop_icon = wx.Bitmap(icons_dir + 'stop_active.png')
|
||||
elif self.timeline._play_speed < 0.0:
|
||||
rewind_icon = wx.Bitmap(icons_dir + 'rewind_active.png')
|
||||
|
||||
start_tool = tb.AddLabelTool(wx.ID_ANY, '', start_icon)
|
||||
rewind_tool = tb.AddLabelTool(wx.ID_ANY, '', rewind_icon)
|
||||
play_tool = tb.AddLabelTool(wx.ID_ANY, '', play_icon)
|
||||
fastforward_tool = tb.AddLabelTool(wx.ID_ANY, '', fastforward_icon)
|
||||
end_tool = tb.AddLabelTool(wx.ID_ANY, '', end_icon)
|
||||
stop_tool = tb.AddLabelTool(wx.ID_ANY, '', stop_icon)
|
||||
if self.timeline.recorder:
|
||||
if self.timeline.recorder.paused:
|
||||
record_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'record_inactive.png'))
|
||||
else:
|
||||
record_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'record.png'))
|
||||
tb.AddSeparator()
|
||||
zoom_in_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'zoom_in.png'))
|
||||
zoom_out_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'zoom_out.png'))
|
||||
zoom_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'zoom.png'))
|
||||
tb.AddSeparator()
|
||||
thumbnails_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'thumbnails.png'))
|
||||
#tb.AddSeparator()
|
||||
#save_layout_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'save_layout.png'))
|
||||
#load_layout_tool = tb.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'load_layout.png'))
|
||||
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_start(), start_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_rewind(), rewind_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_play(), play_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_fastforward(), fastforward_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_end(), end_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_stop(), stop_tool)
|
||||
if self.timeline.recorder:
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.toggle_recording(), record_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.zoom_in(), zoom_in_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.zoom_out(), zoom_out_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.reset_zoom(), zoom_tool)
|
||||
tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.toggle_renderers(), thumbnails_tool)
|
||||
#tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.save_layout(), save_layout_tool)
|
||||
#tb.Bind(wx.EVT_TOOL, lambda e: self.timeline.load_layout(), load_layout_tool)
|
||||
|
||||
tb.Realize()
|
||||
|
||||
def display_popup(self, pos):
|
||||
self.PopupMenu(TimelinePopupMenu(self, self.timeline), pos)
|
||||
|
||||
class TimelinePopupMenu(wx.Menu):
|
||||
"""
|
||||
Timeline popup menu. Allows user to manipulate the timeline view, and open new message views.
|
||||
"""
|
||||
def __init__(self, parent, timeline):
|
||||
def __init__(self, timeline):
|
||||
wx.Menu.__init__(self)
|
||||
|
||||
self.parent = parent
|
||||
self.parent = timeline
|
||||
self.timeline = timeline
|
||||
|
||||
# Reset Timeline
|
||||
|
@ -182,7 +91,7 @@ class TimelinePopupMenu(wx.Menu):
|
|||
renderer_item = self.TimelineRendererMenuItem(self.thumbnail_menu, wx.NewId(), topic.lstrip('/'), topic, renderer, self.timeline)
|
||||
self.thumbnail_menu.AppendItem(renderer_item)
|
||||
|
||||
renderer_item.Check(topic in self.timeline.rendered_topics)
|
||||
renderer_item.Check(self.timeline.is_renderer_active(topic))
|
||||
|
||||
# View (by topic)...
|
||||
self.view_topic_menu = wx.Menu()
|
||||
|
@ -253,6 +162,17 @@ class TimelinePopupMenu(wx.Menu):
|
|||
if self.timeline.selected_left is None or self.timeline.selected_right is None:
|
||||
self.copy_region_menu.Enable(False)
|
||||
|
||||
class PlayAllMenuItem(wx.MenuItem):
|
||||
def __init__(self, parent, id, label, timeline):
|
||||
wx.MenuItem.__init__(self, parent, id, label, kind=wx.ITEM_CHECK)
|
||||
|
||||
self.timeline = timeline
|
||||
|
||||
parent.Bind(wx.EVT_MENU, self.on_menu, id=self.GetId())
|
||||
|
||||
def on_menu(self, event):
|
||||
self.timeline.play_all = not self.timeline.play_all
|
||||
|
||||
class TimelineRendererMenuItem(wx.MenuItem):
|
||||
def __init__(self, parent, id, label, topic, renderer, timeline):
|
||||
wx.MenuItem.__init__(self, parent, id, label, kind=wx.ITEM_CHECK)
|
||||
|
@ -278,24 +198,11 @@ class TimelinePopupMenu(wx.Menu):
|
|||
|
||||
def on_menu(self, event):
|
||||
frame = BaseFrame(None, 'rxbag', self.topic, title='rxbag - %s [%s]' % (self.topic.lstrip('/'), self.viewer_type.name), pos=(4, 4), size=(640, 480))
|
||||
panel = LayerPanel(frame, -1)
|
||||
view = self.viewer_type(self.timeline, panel, self.topic, 0, 0, *frame.GetClientSize())
|
||||
panel.layers = [view]
|
||||
view = self.viewer_type(self.timeline, frame)
|
||||
frame.Show()
|
||||
|
||||
|
||||
self.timeline.add_view(self.topic, view)
|
||||
|
||||
class PlayAllMenuItem(wx.MenuItem):
|
||||
def __init__(self, parent, id, label, timeline):
|
||||
wx.MenuItem.__init__(self, parent, id, label, kind=wx.ITEM_CHECK)
|
||||
|
||||
self.timeline = timeline
|
||||
|
||||
parent.Bind(wx.EVT_MENU, self.on_menu, id=self.GetId())
|
||||
|
||||
def on_menu(self, event):
|
||||
self.timeline.play_all = not self.timeline.play_all
|
||||
|
||||
class PublishTopicMenuItem(wx.MenuItem):
|
||||
def __init__(self, parent, id, topic, timeline):
|
||||
wx.MenuItem.__init__(self, parent, id, topic.lstrip('/'), kind=wx.ITEM_CHECK)
|
71
tools/rxbag/src/rxbag/status.py → tools/rxbag/src/rxbag/timeline_status_bar.py
Executable file → Normal file
71
tools/rxbag/src/rxbag/status.py → tools/rxbag/src/rxbag/timeline_status_bar.py
Executable file → Normal file
|
@ -30,32 +30,58 @@
|
|||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
"""
|
||||
Draws the playhead time indicator and the playspeed.
|
||||
"""
|
||||
|
||||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import wx
|
||||
|
||||
import bag_helper
|
||||
from util.layer import Layer
|
||||
|
||||
class StatusLayer(Layer):
|
||||
def __init__(self, parent, title, timeline, x, y, width, height):
|
||||
Layer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
PlayheadChangedEvent, EVT_PLAYHEAD_CHANGED = wx.lib.newevent.NewEvent()
|
||||
|
||||
class TimelineStatusBar(wx.StatusBar):
|
||||
def __init__(self, parent, timeline):
|
||||
wx.StatusBar.__init__(self, parent, -1)
|
||||
|
||||
self.timeline = timeline
|
||||
|
||||
def paint(self, dc):
|
||||
if not self.timeline.playhead:
|
||||
self.timestamp_field = 1
|
||||
self.human_readable_field = 2
|
||||
self.elapsed_field = 3
|
||||
self.playspeed_field = 4
|
||||
|
||||
self.timestamp_width = 125
|
||||
self.human_readable_width = 180
|
||||
self.elapsed_width = 110
|
||||
self.playspeed_width = 80
|
||||
|
||||
self.SetFieldsCount(5)
|
||||
|
||||
parent.Bind(EVT_PLAYHEAD_CHANGED, lambda e: self._update())
|
||||
parent.Bind(wx.EVT_SIZE, self.on_size)
|
||||
|
||||
self._update()
|
||||
|
||||
def on_size(self, event):
|
||||
main_width = self.Size[0] - (self.timestamp_width + self.human_readable_width + self.elapsed_width + self.playspeed_width)
|
||||
self.SetStatusWidths([main_width, self.timestamp_width, self.human_readable_width, self.elapsed_width, self.playspeed_width])
|
||||
event.Skip()
|
||||
|
||||
def _update(self):
|
||||
if self.timeline.playhead is None or self.timeline.start_stamp is None:
|
||||
return
|
||||
|
||||
s = '%s [%.3fs]' % (bag_helper.stamp_to_str(self.timeline.playhead), (self.timeline.playhead - self.timeline.start_stamp).to_sec())
|
||||
# Raw timestamp
|
||||
self.SetStatusText('%d.%s' % (self.timeline.playhead.secs, str(self.timeline.playhead.nsecs)[:3]), self.timestamp_field)
|
||||
|
||||
# Human-readable time
|
||||
self.SetStatusText(bag_helper.stamp_to_str(self.timeline.playhead), self.human_readable_field)
|
||||
|
||||
# Elapsed time (in seconds)
|
||||
self.SetStatusText('%.3fs' % (self.timeline.playhead - self.timeline.start_stamp).to_sec(), self.elapsed_field)
|
||||
|
||||
# Play speed
|
||||
spd = self.timeline.play_speed
|
||||
spd_str = None
|
||||
if spd != 0.0:
|
||||
if spd > 1.0:
|
||||
spd_str = '>> %.0fx' % spd
|
||||
|
@ -69,20 +95,7 @@ class StatusLayer(Layer):
|
|||
spd_str = '<'
|
||||
else:
|
||||
spd_str = '<< %.0fx' % -spd
|
||||
if spd_str:
|
||||
s += ' ' + spd_str
|
||||
|
||||
x = self.timeline.margin_left
|
||||
y = self.timeline.history_top - 12
|
||||
|
||||
dc.set_source_rgb(0, 0, 0)
|
||||
dc.set_font_size(13.0)
|
||||
dc.move_to(x, y)
|
||||
dc.show_text(s)
|
||||
|
||||
dc.set_source_rgb(0.2, 0.2, 0.2)
|
||||
dc.set_font_size(10.0)
|
||||
s = '%10d.%09d' % (self.timeline.playhead.secs, self.timeline.playhead.nsecs)
|
||||
font_width, font_height = dc.text_extents(s)[2:4]
|
||||
dc.move_to(self.parent.width - font_width - 8, y - 2)
|
||||
dc.show_text(s)
|
||||
self.SetStatusText(spd_str, self.playspeed_field)
|
||||
else:
|
||||
self.SetStatusText('', self.playspeed_field)
|
|
@ -0,0 +1,157 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2009, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
PKG = 'rxbag'
|
||||
import roslib; roslib.load_manifest(PKG)
|
||||
|
||||
import wx
|
||||
|
||||
class TimelineToolBar(wx.ToolBar):
|
||||
def __init__(self, parent, timeline):
|
||||
wx.ToolBar.__init__(self, parent, -1, style=wx.TB_TEXT)
|
||||
|
||||
self.timeline = timeline
|
||||
|
||||
self._state = None
|
||||
|
||||
self._setup()
|
||||
|
||||
def _setup(self):
|
||||
# If state of toolbar hasn't changed, don't recreate the tools
|
||||
new_state = TimelineToolBarState(self.timeline)
|
||||
if new_state == self._state:
|
||||
return
|
||||
|
||||
self._state = new_state
|
||||
|
||||
self.ClearTools()
|
||||
|
||||
icons_dir = roslib.packages.get_pkg_dir(PKG) + '/icons/'
|
||||
|
||||
start_icon = wx.Bitmap(icons_dir + 'start.png')
|
||||
rewind_icon = wx.Bitmap(icons_dir + 'rewind.png')
|
||||
play_icon = wx.Bitmap(icons_dir + 'play.png')
|
||||
fastforward_icon = wx.Bitmap(icons_dir + 'fastforward.png')
|
||||
end_icon = wx.Bitmap(icons_dir + 'end.png')
|
||||
stop_icon = wx.Bitmap(icons_dir + 'stop.png')
|
||||
|
||||
if self.timeline._play_speed > 1.0:
|
||||
fastforward_icon = wx.Bitmap(icons_dir + 'fastforward_active.png')
|
||||
elif self.timeline._play_speed > 0.0:
|
||||
play_icon = wx.Bitmap(icons_dir + 'play_active.png')
|
||||
elif self.timeline._play_speed == 0.0:
|
||||
stop_icon = wx.Bitmap(icons_dir + 'stop_active.png')
|
||||
elif self.timeline._play_speed < 0.0:
|
||||
rewind_icon = wx.Bitmap(icons_dir + 'rewind_active.png')
|
||||
|
||||
idle_renderers = len(self.timeline._rendered_topics) < len(self.timeline.topics)
|
||||
if idle_renderers:
|
||||
thumbnails_icon = wx.Bitmap(icons_dir + 'thumbnails.png')
|
||||
else:
|
||||
thumbnails_icon = wx.Bitmap(icons_dir + 'thumbnails_off.png')
|
||||
|
||||
# Create the tools
|
||||
|
||||
start_tool = self.AddLabelTool(wx.ID_ANY, '', start_icon, shortHelp='Start (Home)', longHelp='Move playhead to start of timeline')
|
||||
rewind_tool = self.AddLabelTool(wx.ID_ANY, '', rewind_icon, shortHelp='Rewind (Numpad -)', longHelp='Rewind')
|
||||
play_tool = self.AddLabelTool(wx.ID_ANY, '', play_icon, shortHelp='Play (Space)', longHelp='Play')
|
||||
fastforward_tool = self.AddLabelTool(wx.ID_ANY, '', fastforward_icon, shortHelp='Fastforward (Numpad +)', longHelp='Fastforward')
|
||||
end_tool = self.AddLabelTool(wx.ID_ANY, '', end_icon, shortHelp='End (End)', longHelp='Move playhead to end of timeline')
|
||||
stop_tool = self.AddLabelTool(wx.ID_ANY, '', stop_icon, shortHelp='Stop (Space)', longHelp='Stop')
|
||||
if self.timeline._recorder:
|
||||
if self.timeline._recorder.paused:
|
||||
record_icon = 'record_inactive.png'
|
||||
else:
|
||||
record_icon = 'record.png'
|
||||
record_tool = self.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + record_icon), shortHelp='Record (Pause)', longHelp='Toggle recording')
|
||||
self.AddSeparator()
|
||||
zoom_in_tool = self.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'zoom_in.png'), shortHelp='Zoom in (Page Up)', longHelp='Zoom in timeline')
|
||||
zoom_out_tool = self.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'zoom_out.png'), shortHelp='Zoom out (Page Down)', longHelp='Zoom out timeline')
|
||||
zoom_tool = self.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'zoom.png'), shortHelp='Reset zoom', longHelp='View entire timeline')
|
||||
self.AddSeparator()
|
||||
thumbnails_tool = self.AddLabelTool(wx.ID_ANY, '', thumbnails_icon, shortHelp='Thumbnails', longHelp='Toggle thumbnails')
|
||||
|
||||
# Bind tools to events
|
||||
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_start(), start_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_rewind(), rewind_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_play(), play_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_fastforward(), fastforward_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_end(), end_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.navigate_stop(), stop_tool)
|
||||
if self.timeline._recorder:
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.toggle_recording(), record_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.zoom_in(), zoom_in_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.zoom_out(), zoom_out_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.reset_zoom(), zoom_tool)
|
||||
self.Bind(wx.EVT_TOOL, lambda e: self.timeline.toggle_renderers(), thumbnails_tool)
|
||||
|
||||
# Set the enabled flag
|
||||
|
||||
if self.timeline._stamp_left is None:
|
||||
for tool in [start_tool, rewind_tool, play_tool, fastforward_tool, end_tool, stop_tool, zoom_in_tool, zoom_out_tool, zoom_tool, thumbnails_tool]:
|
||||
self.EnableTool(tool.Id, False)
|
||||
else:
|
||||
self.EnableTool(zoom_in_tool.Id, self.timeline.can_zoom_in())
|
||||
self.EnableTool(zoom_out_tool.Id, self.timeline.can_zoom_out())
|
||||
|
||||
# Realize the toolbar
|
||||
|
||||
self.Realize()
|
||||
|
||||
class TimelineToolBarState(object):
|
||||
def __init__(self, timeline):
|
||||
self._fastforward_active = timeline._play_speed > 1.0
|
||||
self._play_active = timeline._play_speed > 0.0
|
||||
self._stop_active = timeline._play_speed == 0.0
|
||||
self._rewind_active = timeline._play_speed < 0.0
|
||||
self._idle_renderers = len(timeline._rendered_topics) < len(timeline.topics)
|
||||
self._recorder_visible = timeline._recorder is not None
|
||||
self._recorder_paused = timeline._recorder is not None and timeline._recorder.paused
|
||||
self._timeline_visible = timeline._stamp_left is not None
|
||||
self._can_zoom_in = timeline._stamp_left is not None and timeline.can_zoom_in()
|
||||
self._can_zoom_out = timeline._stamp_left is not None and timeline.can_zoom_out()
|
||||
|
||||
def __eq__(self, other):
|
||||
if other is None:
|
||||
return False
|
||||
|
||||
return self._fastforward_active == other._fastforward_active \
|
||||
and self._play_active == other._play_active \
|
||||
and self._stop_active == other._stop_active \
|
||||
and self._rewind_active == other._rewind_active \
|
||||
and self._idle_renderers == other._idle_renderers \
|
||||
and self._recorder_visible == other._recorder_visible \
|
||||
and self._recorder_paused == other._recorder_paused \
|
||||
and self._timeline_visible == other._timeline_visible \
|
||||
and self._can_zoom_in == other._can_zoom_in \
|
||||
and self._can_zoom_out == other._can_zoom_out
|
|
@ -30,8 +30,6 @@
|
|||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
import sys
|
||||
|
||||
import wx
|
||||
|
||||
class BaseFrame(wx.Frame):
|
||||
|
@ -41,38 +39,42 @@ class BaseFrame(wx.Frame):
|
|||
def __init__(self, parent, config_name, config_key, id=wx.ID_ANY, title='Untitled', pos=wx.DefaultPosition, size=(800, 300), style=wx.DEFAULT_FRAME_STYLE):
|
||||
wx.Frame.__init__(self, parent, id, title, pos, size, style)
|
||||
|
||||
self.config = wx.Config(config_name)
|
||||
self.config_key = config_key
|
||||
self._config = wx.Config(config_name)
|
||||
self._config_key = config_key
|
||||
|
||||
self._load_config()
|
||||
|
||||
self.Bind(wx.EVT_CLOSE, self.on_close)
|
||||
self.Bind(wx.EVT_CLOSE, self._on_close)
|
||||
|
||||
def on_close(self, event):
|
||||
def _on_close(self, event):
|
||||
self._save_config()
|
||||
|
||||
self.Destroy()
|
||||
|
||||
## Load position and size of the frame from config
|
||||
def _load_config(self):
|
||||
(x, y), (width, height) = self.GetPositionTuple(), self.GetSizeTuple()
|
||||
if self.config.HasEntry(self._config_x): x = self.config.ReadInt(self._config_x)
|
||||
if self.config.HasEntry(self._config_y): y = self.config.ReadInt(self._config_y)
|
||||
if self.config.HasEntry(self._config_width): width = self.config.ReadInt(self._config_width)
|
||||
if self.config.HasEntry(self._config_height): height = self.config.ReadInt(self._config_height)
|
||||
"""
|
||||
Load position and size of the frame from config
|
||||
"""
|
||||
(x, y), (width, height) = self.Position, self.Size
|
||||
if self._config.HasEntry(self._config_x): x = self._config.ReadInt(self._config_x)
|
||||
if self._config.HasEntry(self._config_y): y = self._config.ReadInt(self._config_y)
|
||||
if self._config.HasEntry(self._config_width): width = self._config.ReadInt(self._config_width)
|
||||
if self._config.HasEntry(self._config_height): height = self._config.ReadInt(self._config_height)
|
||||
|
||||
self.SetPosition((x, y))
|
||||
self.SetSize((width, height))
|
||||
self.Position = (x, y)
|
||||
self.Size = (width, height)
|
||||
|
||||
## Save position and size of frame to config
|
||||
def _save_config(self):
|
||||
(x, y), (width, height) = self.GetPositionTuple(), self.GetSizeTuple()
|
||||
"""
|
||||
Save position and size of frame to config
|
||||
"""
|
||||
(x, y), (width, height) = self.Position, self.Size
|
||||
|
||||
self.config.WriteInt(self._config_x, x)
|
||||
self.config.WriteInt(self._config_y, y)
|
||||
self.config.WriteInt(self._config_width, width)
|
||||
self.config.WriteInt(self._config_height, height)
|
||||
self.config.Flush()
|
||||
self._config.WriteInt(self._config_x, x)
|
||||
self._config.WriteInt(self._config_y, y)
|
||||
self._config.WriteInt(self._config_width, width)
|
||||
self._config.WriteInt(self._config_height, height)
|
||||
self._config.Flush()
|
||||
|
||||
@property
|
||||
def _config_x(self): return self._config_property('X')
|
||||
|
@ -86,4 +88,4 @@ class BaseFrame(wx.Frame):
|
|||
@property
|
||||
def _config_height(self): return self._config_property('Height')
|
||||
|
||||
def _config_property(self, property): return '/%s/%s' % (self.config_key, property)
|
||||
def _config_property(self, property): return '/%s/%s' % (self._config_key, property)
|
||||
|
|
|
@ -1,293 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2009, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
import time
|
||||
|
||||
import wx
|
||||
import wx.lib.wxcairo
|
||||
|
||||
class Layer(object):
|
||||
name = 'Untitled'
|
||||
|
||||
def __init__(self, parent, title, x, y, width, height):
|
||||
self._x = x
|
||||
self._y = y
|
||||
self._width = width
|
||||
self._height = height
|
||||
|
||||
self.parent = parent
|
||||
self.title = title
|
||||
|
||||
self.self_paint = False
|
||||
|
||||
if not self.self_paint:
|
||||
self.bitmap = wx.EmptyBitmap(self._width, self._height)
|
||||
|
||||
self._last_repaint = None
|
||||
self._dirty = True
|
||||
|
||||
# Interface to implement in derived classes
|
||||
|
||||
def check_dirty(self): pass
|
||||
def paint(self, dc): pass
|
||||
|
||||
def on_mouse_move(self, event): pass
|
||||
def on_mousewheel(self, event): pass
|
||||
def on_left_down(self, event): pass
|
||||
def on_middle_down(self, event): pass
|
||||
def on_right_down(self, event): pass
|
||||
def on_left_up(self, event): pass
|
||||
def on_middle_up(self, event): pass
|
||||
def on_right_up(self, event): pass
|
||||
def on_size(self, event): pass
|
||||
def on_close(self, event): pass
|
||||
|
||||
def move(self, x, y):
|
||||
if self._x == x and self._y == y:
|
||||
return
|
||||
|
||||
self._x, self._y = x, y
|
||||
|
||||
self.invalidate()
|
||||
|
||||
def resize(self, width, height):
|
||||
if self._width == width and self._height == height:
|
||||
return
|
||||
|
||||
self._width, self._height = width, height
|
||||
|
||||
if not self.self_paint:
|
||||
self.bitmap = wx.EmptyBitmap(self._width, self._height)
|
||||
|
||||
self.invalidate()
|
||||
|
||||
def contains(self, x, y):
|
||||
return x >= self._x and y >= self._y and x <= self.right and y <= self.bottom
|
||||
|
||||
def invalidate(self):
|
||||
self._dirty = True
|
||||
wx.CallAfter(self.parent.Refresh)
|
||||
|
||||
@property
|
||||
def x(self): return self._x
|
||||
|
||||
@property
|
||||
def y(self): return self._y
|
||||
|
||||
@property
|
||||
def width(self): return self._width
|
||||
|
||||
@property
|
||||
def height(self): return self._height
|
||||
|
||||
@property
|
||||
def right(self): return self._x + self._width
|
||||
|
||||
@property
|
||||
def bottom(self): return self._y + self._height
|
||||
|
||||
# Painting
|
||||
|
||||
def paint_to_bitmap(self):
|
||||
mem_dc = wx.MemoryDC()
|
||||
mem_dc.SelectObject(self.bitmap)
|
||||
|
||||
self.clear_background(mem_dc)
|
||||
|
||||
cairo_dc = wx.lib.wxcairo.ContextFromDC(mem_dc)
|
||||
self.paint(cairo_dc)
|
||||
|
||||
mem_dc.SelectObject(wx.NullBitmap)
|
||||
|
||||
self._dirty = False
|
||||
|
||||
def clear_background(self, dc):
|
||||
dc.SetBackground(wx.WHITE_BRUSH)
|
||||
dc.Clear()
|
||||
|
||||
def draw(self, dc):
|
||||
if not self.self_paint:
|
||||
dc.DrawBitmap(self.bitmap, self._x, self._y)
|
||||
|
||||
class TransparentLayer(Layer):
|
||||
TRANSPARENT_COLOR = wx.Colour(5, 5, 5)
|
||||
|
||||
def __init__(self, parent, title, x, y, width, height):
|
||||
Layer.__init__(self, parent, title, x, y, width, height)
|
||||
|
||||
self._transparent_bitmap = None
|
||||
|
||||
self.bitmap.SetMask(wx.Mask(self.bitmap, self.TRANSPARENT_COLOR))
|
||||
|
||||
def paint_to_bitmap(self):
|
||||
Layer.paint_to_bitmap(self)
|
||||
|
||||
self._transparent_bitmap = self._make_transparent(self.bitmap)
|
||||
|
||||
def draw(self, dc):
|
||||
if self._transparent_bitmap:
|
||||
dc.DrawBitmap(self._transparent_bitmap, self.x, self.y, useMask=True)
|
||||
|
||||
def paint(self, dc):
|
||||
pass
|
||||
|
||||
def clear_background(self, dc):
|
||||
dc.SetBackground(wx.Brush(self.TRANSPARENT_COLOR, wx.SOLID))
|
||||
dc.Clear()
|
||||
|
||||
## A bug in wxPython with transparent bitmaps: need to convert to/from Image to enable transparency.
|
||||
## (see http://aspn.activestate.com/ASPN/Mail/Message/wxpython-users/3668628)
|
||||
def _make_transparent(self, bitmap):
|
||||
image = bitmap.ConvertToImage()
|
||||
if not image.HasAlpha():
|
||||
image.InitAlpha()
|
||||
|
||||
w, h = image.GetWidth(), image.GetHeight()
|
||||
for y in xrange(h):
|
||||
for x in xrange(w):
|
||||
pix = wx.Colour(image.GetRed(x, y), image.GetGreen(x, y), image.GetBlue(x, y))
|
||||
if pix == self.TRANSPARENT_COLOR:
|
||||
image.SetAlpha(x, y, 0)
|
||||
|
||||
return image.ConvertToBitmap()
|
||||
|
||||
class LayerPanel(wx.Window):
|
||||
def __init__(self, *args, **kwargs):
|
||||
wx.Window.__init__(self, *args, **kwargs)
|
||||
|
||||
self.composite_layers = False
|
||||
|
||||
self.background_brush = wx.WHITE_BRUSH
|
||||
|
||||
self.layers = []
|
||||
self.clicked_pos = None
|
||||
self.painting = False
|
||||
|
||||
self.Bind(wx.EVT_PAINT, self.on_paint)
|
||||
self.Bind(wx.EVT_SIZE, self.on_size)
|
||||
self.Bind(wx.EVT_LEFT_DOWN, self.on_left_down)
|
||||
self.Bind(wx.EVT_MIDDLE_DOWN, self.on_middle_down)
|
||||
self.Bind(wx.EVT_RIGHT_DOWN, self.on_right_down)
|
||||
self.Bind(wx.EVT_LEFT_UP, self.on_left_up)
|
||||
self.Bind(wx.EVT_MIDDLE_UP, self.on_middle_up)
|
||||
self.Bind(wx.EVT_RIGHT_UP, self.on_right_up)
|
||||
self.Bind(wx.EVT_MOTION, self.on_mouse_move)
|
||||
self.Bind(wx.EVT_MOUSEWHEEL, self.on_mousewheel)
|
||||
|
||||
parent = self.GetParent()
|
||||
while parent.GetParent():
|
||||
parent = parent.GetParent()
|
||||
parent.Bind(wx.EVT_CLOSE, self.on_close)
|
||||
|
||||
@property
|
||||
def width(self): return self.Size[0]
|
||||
|
||||
@property
|
||||
def height(self): return self.Size[1]
|
||||
|
||||
# Painting events
|
||||
|
||||
def on_paint(self, event):
|
||||
window_dc = wx.PaintDC(self)
|
||||
window_dc.SetBackground(self.background_brush)
|
||||
window_dc.Clear()
|
||||
|
||||
if self.composite_layers:
|
||||
for layer in self.layers:
|
||||
if not layer.self_paint:
|
||||
layer.check_dirty()
|
||||
if layer._dirty:
|
||||
layer.paint_to_bitmap()
|
||||
|
||||
for layer in self.layers:
|
||||
if not layer.self_paint:
|
||||
layer.draw(window_dc)
|
||||
else:
|
||||
cdc = wx.lib.wxcairo.ContextFromDC(window_dc)
|
||||
|
||||
for layer in self.layers:
|
||||
cdc.save()
|
||||
cdc.translate(layer.x, layer.y)
|
||||
layer.paint(cdc)
|
||||
cdc.restore()
|
||||
|
||||
def on_size(self, event):
|
||||
size = self.GetClientSize()
|
||||
for layer in self.layers:
|
||||
layer.on_size(event)
|
||||
|
||||
# Mouse events
|
||||
|
||||
def on_left_down(self, event):
|
||||
self.clicked_pos = event.GetPosition()
|
||||
for layer in self.layers:
|
||||
layer.on_left_down(event)
|
||||
|
||||
def on_middle_down(self, event):
|
||||
self.clicked_pos = event.GetPosition()
|
||||
for layer in self.layers:
|
||||
layer.on_middle_down(event)
|
||||
|
||||
def on_right_down(self, event):
|
||||
self.clicked_pos = event.GetPosition()
|
||||
for layer in self.layers:
|
||||
layer.on_right_down(event)
|
||||
|
||||
def on_left_up(self, event):
|
||||
self.clicked_pos = event.GetPosition()
|
||||
for layer in self.layers:
|
||||
layer.on_left_up(event)
|
||||
|
||||
def on_middle_up(self, event):
|
||||
self.clicked_pos = event.GetPosition()
|
||||
for layer in self.layers:
|
||||
layer.on_middle_up(event)
|
||||
|
||||
def on_right_up(self, event):
|
||||
self.clicked_pos = event.GetPosition()
|
||||
for layer in self.layers:
|
||||
layer.on_right_up(event)
|
||||
|
||||
def on_mouse_move(self, event):
|
||||
for layer in self.layers:
|
||||
layer.on_mouse_move(event)
|
||||
|
||||
def on_mousewheel(self, event):
|
||||
for layer in self.layers:
|
||||
layer.on_mousewheel(event)
|
||||
|
||||
#
|
||||
|
||||
def on_close(self, event):
|
||||
for layer in self.layers:
|
||||
layer.on_close(event)
|
||||
event.Skip()
|
|
@ -92,9 +92,11 @@ class ProgressMeter:
|
|||
self.step(self.bytes_total, force_update=True)
|
||||
print
|
||||
|
||||
## Convert file size to human-readable form
|
||||
@classmethod
|
||||
def approximate_size(cls, size, a_kilobyte_is_1024_bytes=False):
|
||||
"""
|
||||
Convert file size to human-readable form
|
||||
"""
|
||||
if size < 0:
|
||||
raise ValueError('number must be non-negative')
|
||||
|
||||
|
@ -106,9 +108,11 @@ class ProgressMeter:
|
|||
|
||||
raise ValueError('number too large')
|
||||
|
||||
## Estimate the width of the terminal
|
||||
@staticmethod
|
||||
def terminal_width():
|
||||
"""
|
||||
Estimate the width of the terminal
|
||||
"""
|
||||
width = 0
|
||||
try:
|
||||
import struct, fcntl, termios
|
||||
|
|
Loading…
Reference in New Issue