Skip to content

Commit

Permalink
WIP reverse read order test
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <emerson.b.knapp@gmail.com>
  • Loading branch information
emersonknapp committed Sep 23, 2022
1 parent 34f598f commit b89d2b1
Show file tree
Hide file tree
Showing 4 changed files with 105 additions and 10 deletions.
87 changes: 87 additions & 0 deletions rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <gmock/gmock.h>

#include <filesystem>
#include <memory>
#include <string>
#include <utility>
Expand Down Expand Up @@ -234,3 +235,89 @@ TEST_F(TemporaryDirectoryFixture, reader_accepts_bare_file) {
EXPECT_TRUE(reader.has_next());
EXPECT_THAT(reader.get_metadata().topics_with_message_count, SizeIs(1));
}


class OrderTestWriter : public rosbag2_cpp::writers::SequentialWriter
{
public:
// makes the method public for manual splitting
void split() {
split_bagfile();
}
};


class ReadOrderTest : public TemporaryDirectoryFixture
{
public:
ReadOrderTest()
{
fake_data = std::make_shared<rcutils_uint8_array_t>();
storage_options.uri = (std::filesystem::path(temporary_dir_path_) / "ordertest").string();
storage_options.storage_id = "sqlite3";

writer.open(storage_options, rosbag2_cpp::ConverterOptions{});
for (const auto & file_messages : message_timestamps_by_file) {
for (const auto time_stamp : file_messages) {
auto msg = std::make_shared<rosbag2_storage::SerializedBagMessage>();
msg->serialized_data = fake_data;
msg->time_stamp = time_stamp;
msg->topic_name = topic_name;
writer.write(msg);
}
writer.split();
}
writer.close();
}

const std::vector<std::vector<rcutils_time_point_value_t>> message_timestamps_by_file {
{100, 300, 200},
{500, 400, 600}
};
const std::string topic_name = "testtopic";
OrderTestWriter writer;
rosbag2_cpp::readers::SequentialReader reader;
rosbag2_storage::StorageOptions storage_options;
std::shared_ptr<rcutils_uint8_array_t> fake_data;
};

TEST_F(ReadOrderTest, default_read_order) {
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
auto next = reader.read_next();
ASSERT_EQ(next->time_stamp, 100);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 200);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 300);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 400);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 500);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 600);
ASSERT_FALSE(reader.has_next());
}

TEST_F(ReadOrderTest, reverse_received_timestamp_order) {
rosbag2_storage::ReadOrder order;
order.sort_by = rosbag2_storage::ReadOrder::ReceivedTimestamp;
order.reverse = true;
reader.set_read_order(order);
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
auto metadata = reader.get_metadata();
reader.seek((metadata.starting_time + metadata.duration).time_since_epoch().count());

auto next = reader.read_next();
ASSERT_EQ(next->time_stamp, 600);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 500);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 400);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 300);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 200);
next = reader.read_next();
ASSERT_EQ(next->time_stamp, 100);
ASSERT_FALSE(reader.has_next());
}
15 changes: 12 additions & 3 deletions rosbag2_py/src/rosbag2_py/_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,16 @@ PYBIND11_MODULE(_storage, m) {
return format_bag_meta_data(metadata);
});

pybind11::enum_<rosbag2_storage::ReadOrder>(m, "ReadOrder")
.value("Timestamp", rosbag2_storage::ReadOrder::Timestamp)
.value("ReverseTimestamp", rosbag2_storage::ReadOrder::ReverseTimestamp);
pybind11::enum_<rosbag2_storage::ReadOrder::SortBy>(m, "ReadOrderSortBy")
.value("ReceivedTimestamp", rosbag2_storage::ReadOrder::ReceivedTimestamp)
.value("PublishedTimestamp", rosbag2_storage::ReadOrder::PublishedTimestamp)
.value("File", rosbag2_storage::ReadOrder::File);

pybind11::class_<rosbag2_storage::ReadOrder>(m, "ReadOrder")
.def(
pybind11::init<rosbag2_storage::ReadOrder::SortBy, bool>(),
pybind11::arg("sort_by") = rosbag2_storage::ReadOrder{}.sort_by,
pybind11::arg("reverse") = rosbag2_storage::ReadOrder{}.reverse)
.def_readwrite("sort_by", &rosbag2_storage::ReadOrder::sort_by)
.def_readwrite("reverse", &rosbag2_storage::ReadOrder::reverse);
}
Original file line number Diff line number Diff line change
Expand Up @@ -28,19 +28,19 @@ namespace rosbag2_storage

struct ReadOrder
{
enum SortField {
enum SortBy {
ReceivedTimestamp,
PublishedTimestamp, // NOTE: not yet implemented in ROS 2 core
File
};

// Sorting criterion for reading out messages, ascending by default
SortField order = ReceivedTimestamp;
SortBy sort_by = ReceivedTimestamp;
// If true, changes sort order to descending
bool reverse = false;

bool operator ==(const ReadOrder& other) {
return order == other.order && reverse == other.reverse;
return sort_by == other.sort_by && reverse == other.reverse;
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -294,7 +294,7 @@ void SqliteStorage::set_read_order(rosbag2_storage::ReadOrder read_order)
if (read_order == read_order_) {
return;
}
if (read_order_.order == rosbag2_storage::ReadOrder::PublishedTimestamp) {
if (read_order_.sort_by == rosbag2_storage::ReadOrder::PublishedTimestamp) {
throw std::runtime_error("Not Implemented - PublishedTimestamp read order.");
}
read_order_ = read_order;
Expand Down Expand Up @@ -434,7 +434,7 @@ void SqliteStorage::prepare_for_reading()
std::string message_id_filter = "(messages.id >= " + std::to_string(seek_row_id_) + ")";
std::string timestamp_equal_filter = "(timestamp = " + std::to_string(seek_time_) + ")";
std::string timestamp_greater_filter = "(timestamp > " + std::to_string(seek_time_) + ")";
if (read_order_.order == rosbag2_storage::ReadOrder::File) {
if (read_order_.sort_by == rosbag2_storage::ReadOrder::File) {
statement_str += message_id_filter;
} else {
statement_str += "((" + message_id_filter + " AND " + timestamp_equal_filter + ") "
Expand All @@ -443,8 +443,7 @@ void SqliteStorage::prepare_for_reading()

// add order by time then id
std::string order_direction = read_order_.reverse ? "DESC" : "ASC";
std::string order_by;
switch (read_order_.order) {
switch (read_order_.sort_by) {
case rosbag2_storage::ReadOrder::ReceivedTimestamp:
statement_str += "ORDER BY messages.timestamp " + order_direction +
statement_str += ", messages.id " + order_direction;
Expand Down

0 comments on commit b89d2b1

Please sign in to comment.