rxbag: migrate from rosrecord to rosbag

This commit is contained in:
Tim Field 2010-05-03 23:51:34 +00:00
parent 97f1adaf96
commit f7b8bd957d
3 changed files with 24 additions and 23 deletions

View File

@ -12,7 +12,7 @@
<depend package="rospy"/>
<depend package="roslib"/>
<depend package="std_msgs"/>
<depend package="rosrecord"/>
<depend package="rosbag"/>
<depend package="rxtools"/>
<rosdep name="python-gtk2"/>
<rosdep name="python-matplotlib"/>

View File

@ -35,7 +35,7 @@
PKG = 'rxbag'
import roslib; roslib.load_manifest(PKG)
import rospy
import rosrecord
import rosbag
import bisect
import cPickle
@ -226,22 +226,21 @@ class BagIndexReader:
def load(self):
try:
bag_file = rosrecord.BagReader(self.bag_path)
bag_file = rosbag.Bag(self.bag_path)
if bag_file.read_index() is None:
index = bag_file.get_index()
if index is None:
bag_file.close()
self.index = None
return None
# Read the index in ascending order of topic's first message position (ensures that each datatype message definition gets read)
topic_first_positions = sorted([(ti[0][1], t) for t, ti in bag_file.index.items()])
for _, topic in topic_first_positions:
topic_index = bag_file.index[topic]
datatype = bag_file.datatypes[topic]
for stamp, pos in topic_index:
for (id, topic, datatype), entries in index.items():
for stamp, pos in entries:
self.index.add_record(pos, topic, datatype, stamp)
bag_file.close()
self.index.loaded = True
except Exception, e:
@ -297,20 +296,20 @@ class BagIndexFactory:
def load(self):
try:
bag_file = rosrecord.BagReader(self.bag_path)
bag_file = rosbag.Bag(self.bag_path)
if bag_file.read_index() is not None:
for topic, topic_index in bag_file.index.items():
datatype = bag_file.datatypes[topic]
for stamp, pos in topic_index:
index = bag_file.get_index()
if index is not None:
for (id, topic, datatype), connection_index in index.items():
for stamp, pos in connection_index:
self.index.add_record(pos, topic, datatype, stamp)
else:
file_size = os.path.getsize(self.bag_path)
progress = util.progress_meter.ProgressMeter(self.bag_path, file_size, 1.0)
for i, (pos, topic, raw_msg, stamp) in enumerate(bag_file.raw_messages()):
for i, (pos, topic, raw_msg, stamp) in enumerate(bag_file.read_messages(raw=True)):
(datatype, message_data, md5, bag_pos, pytype) = raw_msg
self.index.add_record(pos, topic, datatype, stamp)
@ -318,6 +317,8 @@ class BagIndexFactory:
progress.step(pos)
progress.finish()
rosbag.close()
self.index.loaded = True

View File

@ -38,7 +38,7 @@ PKG = 'rxbag'
import roslib; roslib.load_manifest(PKG)
import rospy
import rosrecord
import rosbag
import bisect
import collections
@ -76,7 +76,7 @@ class TimelinePanel(LayerPanel):
for i, bag_path in enumerate(input_files):
try:
bag_file = rosrecord.BagReader(bag_path)
bag_file = rosbag.Bag(bag_path)
except Exception, e:
print 'Error loading %s: %s' % (bag_path, e)
continue
@ -108,7 +108,7 @@ class TimelinePanel(LayerPanel):
bag_index = bag_index_factory.index
bag_file = rosrecord.BagReader(bag_path)
bag_file = rosbag.Bag(bag_path)
self.bag_files[bag_file] = bag_index
# Background thread to generate, then save the index
@ -895,7 +895,7 @@ class Timeline(Layer):
if playhead_index is not None:
# Load the message
pos = self.bag_index.msg_positions[topic][playhead_index][1]
(datatype, msg, stamp) = self.bag_file.load_message(pos, self.bag_index)
(datatype, msg, stamp) = self.bag_file._read_message(pos)
msgs[topic] = (stamp, datatype, playhead_index, msg)
continue