Skip to content

Commit

Permalink
set_read_order: return success
Browse files Browse the repository at this point in the history
Signed-off-by: James Smith <james@foxglove.dev>
  • Loading branch information
james-rms committed Nov 23, 2022
1 parent 86efa58 commit 74a7306
Show file tree
Hide file tree
Showing 15 changed files with 46 additions and 35 deletions.
8 changes: 5 additions & 3 deletions rosbag2_cpp/include/rosbag2_cpp/reader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,10 +104,12 @@ class ROSBAG2_CPP_PUBLIC Reader
* read head timestamp.
*
* \param read_order Sorting criterion and direction to read messages in
* \note Calling set_read_order(order) concurrently with has_next(), seek(t), has_next_file()
* or load_next_file() will cause undefined behavior
* \return true if the requested read order has been successfully set.
* \note set_read_order(order) should be called only after open(). Calling set_read_order(order)
* concurrently with has_next(), seek(t), has_next_file() or load_next_file() will cause
* undefined behavior.
*/
void set_read_order(const rosbag2_storage::ReadOrder & read_order);
bool set_read_order(const rosbag2_storage::ReadOrder & read_order);

/**
* Ask whether the underlying bagfile contains at least one more message.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class ROSBAG2_CPP_PUBLIC BaseReaderInterface

virtual void close() = 0;

virtual void set_read_order(const rosbag2_storage::ReadOrder &) = 0;
virtual bool set_read_order(const rosbag2_storage::ReadOrder &) = 0;

virtual bool has_next() = 0;

Expand Down
7 changes: 4 additions & 3 deletions rosbag2_cpp/include/rosbag2_cpp/readers/sequential_reader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,10 +67,11 @@ class ROSBAG2_CPP_PUBLIC SequentialReader
void close() override;

/**
* \note Calling set_read_order(order) concurrently with has_next(), seek(t), has_next_file()
* or load_next_file() will cause undefined behavior
* \note set_read_order(order) should be called only after open(). Calling set_read_order(order)
* concurrently with has_next(), seek(t), has_next_file() or load_next_file() will cause
* undefined behavior.
*/
void set_read_order(const rosbag2_storage::ReadOrder & order) override;
bool set_read_order(const rosbag2_storage::ReadOrder & order) override;

bool has_next() override;

Expand Down
2 changes: 1 addition & 1 deletion rosbag2_cpp/src/rosbag2_cpp/reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ void Reader::close()
reader_impl_->close();
}

void Reader::set_read_order(const rosbag2_storage::ReadOrder & order)
bool Reader::set_read_order(const rosbag2_storage::ReadOrder & order)
{
return reader_impl_->set_read_order(order);
}
Expand Down
12 changes: 8 additions & 4 deletions rosbag2_cpp/src/rosbag2_cpp/readers/sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,10 @@ void SequentialReader::open(
if (!storage_) {
throw std::runtime_error{"No storage could be initialized from the inputs."};
}
storage_->set_read_order(read_order_);
if (!set_read_order(read_order_)) {
ROSBAG2_CPP_LOG_WARN(
"Could not set read order on open(), defaulting to storage plugin's default read order");
}
metadata_ = storage_->get_metadata();
if (metadata_.relative_file_paths.empty()) {
ROSBAG2_CPP_LOG_WARN("No file paths were found in metadata.");
Expand All @@ -129,12 +132,13 @@ void SequentialReader::open(
topics[0].topic_metadata.serialization_format);
}

void SequentialReader::set_read_order(const rosbag2_storage::ReadOrder & order)
bool SequentialReader::set_read_order(const rosbag2_storage::ReadOrder & order)
{
if (storage_) {
storage_->set_read_order(order);
if (!storage_) {
throw std::runtime_error("read order can only be set after open()");
}
read_order_ = order;
return storage_->set_read_order(read_order_);
}

bool SequentialReader::has_next()
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_cpp/test/rosbag2_cpp/mock_storage.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class MockStorage : public rosbag2_storage::storage_interfaces::ReadWriteInterfa
MOCK_METHOD1(update_metadata, void(const rosbag2_storage::BagMetadata &));
MOCK_METHOD1(create_topic, void(const rosbag2_storage::TopicMetadata &));
MOCK_METHOD1(remove_topic, void(const rosbag2_storage::TopicMetadata &));
MOCK_METHOD1(set_read_order, void(const rosbag2_storage::ReadOrder &));
MOCK_METHOD1(set_read_order, bool(const rosbag2_storage::ReadOrder &));
MOCK_METHOD0(has_next, bool());
MOCK_METHOD0(has_next_file, bool());
MOCK_METHOD0(read_next, std::shared_ptr<rosbag2_storage::SerializedBagMessage>());
Expand Down
19 changes: 8 additions & 11 deletions rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,10 +327,10 @@ class ReadOrderTest : public TemporaryDirectoryFixture
TEST_F(ReadOrderTest, received_timestamp_order) {
rosbag2_storage::ReadOrder order(rosbag2_storage::ReadOrder::ReceivedTimestamp, false);
sort_expected(order);
reader.set_read_order(order);

for (bool do_reset : {false, true}) {
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
EXPECT_TRUE(reader.set_read_order(order));
check_against_sorted(do_reset);
reader.close();
}
Expand All @@ -339,8 +339,8 @@ TEST_F(ReadOrderTest, received_timestamp_order) {
TEST_F(ReadOrderTest, reverse_received_timestamp_order) {
rosbag2_storage::ReadOrder order(rosbag2_storage::ReadOrder::ReceivedTimestamp, true);
sort_expected(order);
reader.set_read_order(order);
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
EXPECT_TRUE(reader.set_read_order(order));
auto metadata = reader.get_metadata();
// Seek to end before reading reverse messages
auto end_timestamp = (metadata.starting_time + metadata.duration).time_since_epoch().count();
Expand All @@ -356,22 +356,19 @@ TEST_F(ReadOrderTest, reverse_received_timestamp_order) {

TEST_F(ReadOrderTest, file_order) {
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
EXPECT_THROW(
reader.set_read_order(rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::File, false)),
std::runtime_error);
EXPECT_FALSE(
reader.set_read_order(rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::File, false)));
}

TEST_F(ReadOrderTest, reverse_file_order) {
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
EXPECT_THROW(
reader.set_read_order(rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::File, true)),
std::runtime_error);
EXPECT_FALSE(
reader.set_read_order(rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::File, true)));
}

TEST_F(ReadOrderTest, published_timestamp_order) {
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
EXPECT_THROW(
EXPECT_FALSE(
reader.set_read_order(
rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::PublishedTimestamp, false)),
std::runtime_error);
rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::PublishedTimestamp, false)));
}
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,10 @@ class ROSBAG2_STORAGE_PUBLIC BaseReadInterface
/// This affects the outcome of has_next and read_next.
/// Note that when setting to reverse order, this will not change the read head, so user
/// must first seek() to the end in order to read messages from the end.
/// Also note that set_read_order should only be called after open() has been called.
/// @param read_order The order in which to return messages.
virtual void set_read_order(const ReadOrder & read_order) = 0;
/// @return true if the requested read order has been successfully set.
virtual bool set_read_order(const ReadOrder & read_order) = 0;

virtual bool has_next() = 0;

Expand Down
3 changes: 2 additions & 1 deletion rosbag2_storage/test/rosbag2_storage/test_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,10 @@ void TestPlugin::update_metadata(const rosbag2_storage::BagMetadata & metadata)
(void)metadata;
}

void TestPlugin::set_read_order(const rosbag2_storage::ReadOrder & order)
bool TestPlugin::set_read_order(const rosbag2_storage::ReadOrder & order)
{
std::cout << "Set read order " << order.sort_by << " " << order.reverse << std::endl;
return true;
}

bool TestPlugin::has_next()
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_storage/test/rosbag2_storage/test_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class TestPlugin : public rosbag2_storage::storage_interfaces::ReadWriteInterfac

void remove_topic(const rosbag2_storage::TopicMetadata & topic) override;

void set_read_order(const rosbag2_storage::ReadOrder &) override;
bool set_read_order(const rosbag2_storage::ReadOrder &) override;

bool has_next() override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,10 @@ void TestReadOnlyPlugin::open(
std::cout << "config file uri: " << storage_options.storage_config_uri << ".\n";
}

void TestReadOnlyPlugin::set_read_order(const rosbag2_storage::ReadOrder & order)
bool TestReadOnlyPlugin::set_read_order(const rosbag2_storage::ReadOrder & order)
{
std::cout << "Set read order " << order.sort_by << " " << order.reverse << std::endl;
return true;
}

bool TestReadOnlyPlugin::has_next()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class TestReadOnlyPlugin : public rosbag2_storage::storage_interfaces::ReadOnlyI
const rosbag2_storage::StorageOptions & storage_options,
rosbag2_storage::storage_interfaces::IOFlag flag) override;

void set_read_order(const rosbag2_storage::ReadOrder &) override;
bool set_read_order(const rosbag2_storage::ReadOrder &) override;

bool has_next() override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage
const std::vector<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>> & messages)
override;

void set_read_order(const rosbag2_storage::ReadOrder &) override;
bool set_read_order(const rosbag2_storage::ReadOrder &) override;

bool has_next() override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -320,17 +320,18 @@ void SqliteStorage::write(
commit_transaction();
}

void SqliteStorage::set_read_order(const rosbag2_storage::ReadOrder & read_order)
bool SqliteStorage::set_read_order(const rosbag2_storage::ReadOrder & read_order)
{
if (read_order.sort_by == rosbag2_storage::ReadOrder::PublishedTimestamp) {
throw std::runtime_error("Not Implemented - PublishedTimestamp read order.");
return false;
}
if (read_order.sort_by == rosbag2_storage::ReadOrder::File) {
throw std::runtime_error("Not Implemented - File read order");
return false;
}

read_order_ = read_order;
read_statement_ = nullptr;
return true;
}

bool SqliteStorage::has_next()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,10 @@ class MockSequentialReader : public rosbag2_cpp::reader_interfaces::BaseReaderIn

void close() override {}

void set_read_order(const rosbag2_storage::ReadOrder &) override
{}
bool set_read_order(const rosbag2_storage::ReadOrder &) override
{
return true;
}

bool has_next() override
{
Expand Down

0 comments on commit 74a7306

Please sign in to comment.