rxbag: fixing timeline alpha
This commit is contained in:
parent
74b3305e55
commit
185947eff8
|
@ -126,10 +126,10 @@ class TopicMessageView(MessageView):
|
|||
|
||||
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'))
|
||||
navigate_first_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_first.png'), shortHelp='First message', longHelp='Move playhead to first message on topic')
|
||||
navigate_previous_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_previous.png'), shortHelp='Previous message', longHelp='Move playhead to previous message on topic')
|
||||
navigate_next_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_next.png'), shortHelp='Next message', longHelp='Move playhead to next message on topic')
|
||||
navigate_last_tool = self._toolbar.AddLabelTool(wx.ID_ANY, '', wx.Bitmap(icons_dir + 'navigate_last.png'), shortHelp='Last message', longHelp='Move playhead to last message on topic')
|
||||
|
||||
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)
|
||||
|
|
|
@ -125,14 +125,14 @@ class Timeline(wx.Window):
|
|||
|
||||
# Time ticks
|
||||
|
||||
self._default_datatype_color = (0.0, 0.0, 0.4)
|
||||
self._default_datatype_color = (0.0, 0.0, 0.4, 0.8)
|
||||
self._datatype_colors = {
|
||||
'sensor_msgs/CameraInfo': ( 0, 0, 0.6),
|
||||
'sensor_msgs/Image': ( 0, 0.3, 0.3),
|
||||
'sensor_msgs/LaserScan': (0.6, 0, 0),
|
||||
'pr2_msgs/LaserScannerSignal': (0.6, 0, 0),
|
||||
'pr2_mechanism_msgs/MechanismState': ( 0, 0.6, 0),
|
||||
'tf/tfMessage': ( 0, 0.6, 0),
|
||||
'sensor_msgs/CameraInfo': ( 0, 0, 0.6, 0.8),
|
||||
'sensor_msgs/Image': ( 0, 0.3, 0.3, 0.8),
|
||||
'sensor_msgs/LaserScan': (0.6, 0, 0, 0.8),
|
||||
'pr2_msgs/LaserScannerSignal': (0.6, 0, 0, 0.8),
|
||||
'pr2_mechanism_msgs/MechanismState': ( 0, 0.6, 0, 0.8),
|
||||
'tf/tfMessage': ( 0, 0.6, 0, 0.8),
|
||||
}
|
||||
|
||||
self._default_msg_combine_px = 1.0
|
||||
|
@ -1307,7 +1307,7 @@ class Timeline(wx.Window):
|
|||
|
||||
# Draw stamps
|
||||
dc.set_line_width(1)
|
||||
dc.set_source_rgb(*datatype_color)
|
||||
dc.set_source_rgba(*datatype_color)
|
||||
|
||||
for (stamp_start, stamp_end) in self._find_regions(all_stamps[:end_index], self.map_dx_to_dstamp(self._default_msg_combine_px)):
|
||||
if stamp_end < self._stamp_left:
|
||||
|
|
Loading…
Reference in New Issue