Skip to content

Commit

Permalink
fix regressions from 1372 (#1473)
Browse files Browse the repository at this point in the history
* make new argument optional to restore API compatibility

* Fix rosbag's internal _read_message API

* Correct return_connection_header's default value from None to False

* Add return_connection_header=False arg

... to seek_and_read_message_data_record, for BagReady102.

Otherwise we get this error (e.g. using rqt_bag):
  File ".../lib/python2.7/dist-packages/rosbag/bag.py", line 1299, in _read_message
    return self._reader.seek_and_read_message_data_record(position, raw)
    TypeError: seek_and_read_message_data_record() takes exactly 4 arguments (3 given)
  • Loading branch information
dirk-thomas authored Aug 6, 2018
1 parent 36d5416 commit 3512ae8
Showing 1 changed file with 11 additions and 8 deletions.
19 changes: 11 additions & 8 deletions tools/rosbag/src/rosbag/bag.py
Original file line number Diff line number Diff line change
Expand Up @@ -1291,12 +1291,12 @@ def _uncompressed_size(self):

return sum((h.uncompressed_size for h in self._chunk_headers.values()))

def _read_message(self, position, raw=False):
def _read_message(self, position, raw=False, return_connection_header=False):
"""
Read the message from the given position in the file.
"""
self.flush()
return self._reader.seek_and_read_message_data_record(position, raw)
return self._reader.seek_and_read_message_data_record(position, raw, return_connection_header)

# Index accessing

Expand Down Expand Up @@ -2052,7 +2052,7 @@ def __init__(self, bag):
def start_reading(self):
raise NotImplementedError()

def read_messages(self, topics, start_time, end_time, connection_filter, raw, return_connection_header):
def read_messages(self, topics, start_time, end_time, connection_filter, raw, return_connection_header=False):
raise NotImplementedError()

def reindex(self):
Expand Down Expand Up @@ -2117,7 +2117,7 @@ def reindex(self):

offset = f.tell()

def read_messages(self, topics, start_time, end_time, topic_filter, raw, return_connection_header):
def read_messages(self, topics, start_time, end_time, topic_filter, raw, return_connection_header=False):
f = self.bag._file

f.seek(self.bag._file_header_pos)
Expand Down Expand Up @@ -2355,7 +2355,7 @@ def read_topic_index_record(self):

return (topic, topic_index)

def seek_and_read_message_data_record(self, position, raw):
def seek_and_read_message_data_record(self, position, raw, return_connection_header=False):
f = self.bag._file

# Seek to the message position
Expand Down Expand Up @@ -2399,7 +2399,10 @@ def seek_and_read_message_data_record(self, position, raw):
msg = msg_type()
msg.deserialize(data)

return BagMessage(topic, msg, t)
if return_connection_header:
return BagMessageWithConnectionHeader(topic, msg, t, header)
else:
return BagMessage(topic, msg, t)

class _BagReader200(_BagReader):
"""
Expand Down Expand Up @@ -2670,7 +2673,7 @@ def _read_connection_index_records(self):

self.bag._connection_indexes_read = True

def read_messages(self, topics, start_time, end_time, connection_filter, raw, return_connection_header):
def read_messages(self, topics, start_time, end_time, connection_filter, raw, return_connection_header=False):
connections = self.bag._get_connections(topics, connection_filter)
for entry in self.bag._get_entries(connections, start_time, end_time):
yield self.seek_and_read_message_data_record((entry.chunk_pos, entry.offset), raw, return_connection_header)
Expand Down Expand Up @@ -2774,7 +2777,7 @@ def read_connection_index_record(self):

return (connection_id, index)

def seek_and_read_message_data_record(self, position, raw, return_connection_header):
def seek_and_read_message_data_record(self, position, raw, return_connection_header=False):
chunk_pos, offset = position

chunk_header = self.bag._chunk_headers.get(chunk_pos)
Expand Down

0 comments on commit 3512ae8

Please sign in to comment.