diff --git a/mcap_vendor/CMakeLists.txt b/mcap_vendor/CMakeLists.txt
index 25c008daf..239a80700 100644
--- a/mcap_vendor/CMakeLists.txt
+++ b/mcap_vendor/CMakeLists.txt
@@ -28,7 +28,7 @@ macro(build_mcap_vendor)
include(FetchContent)
fetchcontent_declare(mcap
GIT_REPOSITORY https://github.com/foxglove/mcap.git
- GIT_TAG dc6561d9ba867901709e36526dcf7f7359861e9c # releases/cpp/v0.7.0
+ GIT_TAG 801c4ae3f34b23e9a27eb34b88ab7a0180d4b40f # v0.8.0
)
fetchcontent_makeavailable(mcap)
diff --git a/ros2bag/package.xml b/ros2bag/package.xml
index 5850b429e..b6c054baf 100644
--- a/ros2bag/package.xml
+++ b/ros2bag/package.xml
@@ -22,6 +22,7 @@
launch_testing
launch_testing_ros
python3-pytest
+ rosbag2_storage_default_plugins
ament_python
diff --git a/rosbag2_cpp/package.xml b/rosbag2_cpp/package.xml
index 9e6bdaca6..9dfa3b293 100644
--- a/rosbag2_cpp/package.xml
+++ b/rosbag2_cpp/package.xml
@@ -26,7 +26,9 @@
rosidl_typesupport_introspection_cpp
shared_queues_vendor
- rosbag2_storage_default_plugins
+ rosbag2_storage_default_plugins
+
+ rosbag2_storage_mcap
ament_cmake_gmock
ament_lint_auto
diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp
index 8db3c65e9..9ef8afdfa 100644
--- a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp
+++ b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp
@@ -25,18 +25,18 @@
#include "rosbag2_cpp/writer.hpp"
#include "rosbag2_storage/bag_metadata.hpp"
-#include "rosbag2_storage/default_storage_id.hpp"
#include "rosbag2_storage/metadata_io.hpp"
#include "rosbag2_test_common/temporary_directory_fixture.hpp"
+#include "rosbag2_test_common/tested_storage_ids.hpp"
#include "test_msgs/msg/basic_types.hpp"
using namespace ::testing; // NOLINT
-using rosbag2_test_common::TemporaryDirectoryFixture;
+using rosbag2_test_common::ParametrizedTemporaryDirectoryFixture;
-TEST_F(TemporaryDirectoryFixture, read_metadata_supports_version_2) {
- const auto expected_storage_id = rosbag2_storage::get_default_storage_id();
+TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_2) {
+ const auto expected_storage_id = GetParam();
const std::string bagfile = "rosbag2_bagfile_information:\n"
" version: 2\n"
" storage_identifier: " + expected_storage_id + "\n"
@@ -102,10 +102,9 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_supports_version_2) {
}
}
-TEST_F(TemporaryDirectoryFixture, read_metadata_supports_version_6) {
- const auto expected_storage_id = rosbag2_storage::get_default_storage_id();
+TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_6) {
+ const auto expected_storage_id = GetParam();
const auto expected_storage_file = "test.testbag";
-
const std::string bagfile = "rosbag2_bagfile_information:\n"
" version: 6\n"
" storage_identifier: " + expected_storage_id + "\n"
@@ -203,8 +202,10 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_supports_version_6) {
}
}
-TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metadata_io_method) {
- const auto expected_storage_id = rosbag2_storage::get_default_storage_id();
+TEST_P(
+ ParametrizedTemporaryDirectoryFixture,
+ read_metadata_makes_appropriate_call_to_metadata_io_method) {
+ const auto expected_storage_id = GetParam();
std::string bagfile(
"rosbag2_bagfile_information:\n"
" version: 3\n"
@@ -282,12 +283,16 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada
EXPECT_EQ(read_metadata.compression_mode, "FILE");
}
-TEST_F(TemporaryDirectoryFixture, info_for_standalone_bagfile) {
+TEST_P(ParametrizedTemporaryDirectoryFixture, info_for_standalone_bagfile) {
+ const auto storage_id = GetParam();
const auto bag_path = rcpputils::fs::path(temporary_dir_path_) / "bag";
{
// Create an empty bag with default storage
rosbag2_cpp::Writer writer;
- writer.open(bag_path.string());
+ rosbag2_storage::StorageOptions storage_options;
+ storage_options.storage_id = storage_id;
+ storage_options.uri = bag_path.string();
+ writer.open(storage_options);
test_msgs::msg::BasicTypes msg;
writer.write(msg, "testtopic", rclcpp::Time{});
}
@@ -305,3 +310,9 @@ TEST_F(TemporaryDirectoryFixture, info_for_standalone_bagfile) {
);
EXPECT_THAT(metadata.topics_with_message_count, SizeIs(1));
}
+
+INSTANTIATE_TEST_SUITE_P(
+ RosbagInfoTests,
+ ParametrizedTemporaryDirectoryFixture,
+ ValuesIn(rosbag2_test_common::kTestedStorageIDs)
+);
diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp
index ff4c03bc1..69dd36ac3 100644
--- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp
+++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp
@@ -26,11 +26,11 @@
#include "rosbag2_cpp/writer.hpp"
#include "rosbag2_storage/bag_metadata.hpp"
-#include "rosbag2_storage/default_storage_id.hpp"
#include "rosbag2_storage/metadata_io.hpp"
#include "rosbag2_storage/ros_helper.hpp"
#include "rosbag2_storage/topic_metadata.hpp"
+#include "rosbag2_test_common/tested_storage_ids.hpp"
#include "rosbag2_test_common/temporary_directory_fixture.hpp"
#include "test_msgs/msg/basic_types.hpp"
@@ -43,7 +43,7 @@
#include "mock_storage_factory.hpp"
using namespace testing; // NOLINT
-using rosbag2_test_common::TemporaryDirectoryFixture;
+using rosbag2_test_common::ParametrizedTemporaryDirectoryFixture;
class SequentialReaderTest : public Test
{
@@ -221,13 +221,17 @@ TEST_F(SequentialReaderTest, next_file_calls_callback) {
EXPECT_EQ(opened_file, bag_file_2_path_.string());
}
-TEST_F(TemporaryDirectoryFixture, reader_accepts_bare_file) {
+TEST_P(ParametrizedTemporaryDirectoryFixture, reader_accepts_bare_file) {
const auto bag_path = rcpputils::fs::path(temporary_dir_path_) / "bag";
+ const auto storage_id = GetParam();
{
// Create an empty bag with default storage
rosbag2_cpp::Writer writer;
- writer.open(bag_path.string());
+ rosbag2_storage::StorageOptions options;
+ options.uri = bag_path.string();
+ options.storage_id = storage_id;
+ writer.open(options);
test_msgs::msg::BasicTypes msg;
writer.write(msg, "testtopic", rclcpp::Time{});
}
@@ -241,14 +245,20 @@ TEST_F(TemporaryDirectoryFixture, reader_accepts_bare_file) {
EXPECT_THAT(reader.get_metadata().topics_with_message_count, SizeIs(1));
}
+INSTANTIATE_TEST_SUITE_P(
+ BareFileTests,
+ ParametrizedTemporaryDirectoryFixture,
+ ValuesIn(rosbag2_test_common::kTestedStorageIDs)
+);
-class ReadOrderTest : public TemporaryDirectoryFixture
+
+class ReadOrderTest : public ParametrizedTemporaryDirectoryFixture
{
public:
ReadOrderTest()
{
storage_options.uri = (rcpputils::fs::path(temporary_dir_path_) / "ordertest").string();
- storage_options.storage_id = rosbag2_storage::get_default_storage_id();
+ storage_options.storage_id = GetParam();
write_sample_split_bag(storage_options, fake_messages, split_every);
}
@@ -328,7 +338,7 @@ class ReadOrderTest : public TemporaryDirectoryFixture
rosbag2_storage::StorageOptions storage_options{};
};
-TEST_F(ReadOrderTest, received_timestamp_order) {
+TEST_P(ReadOrderTest, received_timestamp_order) {
rosbag2_storage::ReadOrder order(rosbag2_storage::ReadOrder::ReceivedTimestamp, false);
sort_expected(order);
@@ -340,7 +350,7 @@ TEST_F(ReadOrderTest, received_timestamp_order) {
}
}
-TEST_F(ReadOrderTest, reverse_received_timestamp_order) {
+TEST_P(ReadOrderTest, reverse_received_timestamp_order) {
rosbag2_storage::ReadOrder order(rosbag2_storage::ReadOrder::ReceivedTimestamp, true);
sort_expected(order);
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
@@ -358,21 +368,21 @@ TEST_F(ReadOrderTest, reverse_received_timestamp_order) {
}
}
-TEST_F(ReadOrderTest, file_order) {
- reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
- EXPECT_FALSE(
- reader.set_read_order(rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::File, false)));
-}
-
-TEST_F(ReadOrderTest, reverse_file_order) {
+TEST_P(ReadOrderTest, reverse_file_order) {
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
EXPECT_FALSE(
reader.set_read_order(rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::File, true)));
}
-TEST_F(ReadOrderTest, published_timestamp_order) {
+TEST_P(ReadOrderTest, published_timestamp_order) {
reader.open(storage_options, rosbag2_cpp::ConverterOptions{});
EXPECT_FALSE(
reader.set_read_order(
rosbag2_storage::ReadOrder(rosbag2_storage::ReadOrder::PublishedTimestamp, false)));
}
+
+INSTANTIATE_TEST_SUITE_P(
+ ThisReadOrderTest,
+ ReadOrderTest,
+ ValuesIn(rosbag2_test_common::kTestedStorageIDs)
+);
diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp
index e2e50f714..58978f5d3 100644
--- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp
+++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp
@@ -26,11 +26,11 @@
#include "rosbag2_cpp/writer.hpp"
#include "rosbag2_storage/bag_metadata.hpp"
-#include "rosbag2_storage/default_storage_id.hpp"
#include "rosbag2_storage/ros_helper.hpp"
#include "rosbag2_storage/topic_metadata.hpp"
#include "rosbag2_test_common/temporary_directory_fixture.hpp"
+#include "rosbag2_test_common/tested_storage_ids.hpp"
#include "fake_data.hpp"
#include "mock_converter.hpp"
@@ -40,7 +40,7 @@
#include "mock_storage_factory.hpp"
using namespace testing; // NOLINT
-using rosbag2_test_common::TemporaryDirectoryFixture;
+using rosbag2_test_common::ParametrizedTemporaryDirectoryFixture;
class SequentialWriterTest : public Test
{
@@ -642,8 +642,7 @@ TEST_F(SequentialWriterTest, split_event_calls_callback)
EXPECT_EQ(opened_file, fake_storage_uri_);
}
-
-TEST_F(TemporaryDirectoryFixture, split_bag_metadata_has_full_duration) {
+TEST_P(ParametrizedTemporaryDirectoryFixture, split_bag_metadata_has_full_duration) {
const std::vector> fake_messages {
{100, 1},
{300, 2},
@@ -654,7 +653,7 @@ TEST_F(TemporaryDirectoryFixture, split_bag_metadata_has_full_duration) {
};
rosbag2_storage::StorageOptions storage_options;
storage_options.uri = (rcpputils::fs::path(temporary_dir_path_) / "split_duration_bag").string();
- storage_options.storage_id = rosbag2_storage::get_default_storage_id();
+ storage_options.storage_id = GetParam();
write_sample_split_bag(storage_options, fake_messages, 3);
rosbag2_storage::MetadataIo metadata_io;
@@ -664,3 +663,9 @@ TEST_F(TemporaryDirectoryFixture, split_bag_metadata_has_full_duration) {
std::chrono::high_resolution_clock::time_point(std::chrono::nanoseconds(100)));
ASSERT_EQ(metadata.duration, std::chrono::nanoseconds(500));
}
+
+INSTANTIATE_TEST_SUITE_P(
+ SplitMetadataTest,
+ ParametrizedTemporaryDirectoryFixture,
+ ValuesIn(rosbag2_test_common::kTestedStorageIDs)
+);
diff --git a/rosbag2_storage_mcap/CMakeLists.txt b/rosbag2_storage_mcap/CMakeLists.txt
index b93c53dfe..e07790479 100644
--- a/rosbag2_storage_mcap/CMakeLists.txt
+++ b/rosbag2_storage_mcap/CMakeLists.txt
@@ -85,7 +85,6 @@ if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(rcpputils REQUIRED)
- find_package(rosbag2_cpp REQUIRED)
find_package(rosbag2_test_common REQUIRED)
find_package(std_msgs REQUIRED)
@@ -101,7 +100,7 @@ if(BUILD_TESTING)
ament_add_gmock(test_mcap_storage test/rosbag2_storage_mcap/test_mcap_storage.cpp)
target_link_libraries(test_mcap_storage ${PROJECT_NAME})
- ament_target_dependencies(test_mcap_storage rosbag2_storage rosbag2_cpp rosbag2_test_common std_msgs)
+ ament_target_dependencies(test_mcap_storage rosbag2_storage rosbag2_test_common std_msgs)
target_compile_definitions(test_mcap_storage PRIVATE ${MCAP_COMPILE_DEFS})
ament_add_gmock(test_message_definition_cache test/rosbag2_storage_mcap/test_message_definition_cache.cpp)
diff --git a/rosbag2_storage_mcap/package.xml b/rosbag2_storage_mcap/package.xml
index 84df948d5..f55420da0 100644
--- a/rosbag2_storage_mcap/package.xml
+++ b/rosbag2_storage_mcap/package.xml
@@ -21,7 +21,6 @@
ament_lint_auto
ament_lint_common
rcpputils
- rosbag2_cpp
rosbag2_test_common
std_msgs
rosbag2_storage_mcap_testdata
diff --git a/rosbag2_storage_mcap/src/mcap_storage.cpp b/rosbag2_storage_mcap/src/mcap_storage.cpp
index 3ad2ca2b9..2b7e3f1ed 100644
--- a/rosbag2_storage_mcap/src/mcap_storage.cpp
+++ b/rosbag2_storage_mcap/src/mcap_storage.cpp
@@ -220,8 +220,9 @@ class MCAPStorage : public rosbag2_storage::storage_interfaces::ReadWriteInterfa
rosbag2_storage::storage_interfaces::IOFlag io_flag,
const std::string & storage_config_uri);
- void reset_iterator(rcutils_time_point_value_t start_time = 0);
+ void reset_iterator();
bool read_and_enqueue_message();
+ bool enqueued_message_is_already_read();
bool message_indexes_present();
void ensure_summary_read();
@@ -247,6 +248,9 @@ class MCAPStorage : public rosbag2_storage::storage_interfaces::ReadWriteInterfa
rosbag2_storage_mcap::internal::MessageDefinitionCache msgdef_cache_{};
bool has_read_summary_ = false;
+ rcutils_time_point_value_t last_read_time_point_ = 0;
+ std::optional last_read_message_offset_;
+ std::optional last_enqueued_message_offset_;
};
MCAPStorage::MCAPStorage()
@@ -318,6 +322,7 @@ void MCAPStorage::open_impl(const std::string & uri, const std::string & preset_
if (!status.ok()) {
throw std::runtime_error(status.message);
}
+ last_read_time_point_ = 0;
reset_iterator();
break;
}
@@ -437,20 +442,18 @@ bool MCAPStorage::read_and_enqueue_message()
if (!linear_iterator_) {
return false;
}
- // Already have popped and queued the next message.
- if (next_ != nullptr) {
- return true;
- }
auto & it = *linear_iterator_;
// At the end of the recording
if (it == linear_view_->end()) {
+ next_ = nullptr;
return false;
}
const auto & messageView = *it;
auto msg = std::make_shared();
+ last_enqueued_message_offset_ = messageView.messageOffset;
msg->time_stamp = rcutils_time_point_value_t(messageView.message.logTime);
msg->topic_name = messageView.channel->topic;
msg->serialized_data = rosbag2_storage::make_serialized_message(messageView.message.data,
@@ -463,11 +466,20 @@ bool MCAPStorage::read_and_enqueue_message()
return true;
}
-void MCAPStorage::reset_iterator(rcutils_time_point_value_t start_time)
+void MCAPStorage::reset_iterator()
{
ensure_summary_read();
mcap::ReadMessageOptions options;
- options.startTime = mcap::Timestamp(start_time);
+ if (read_order_ == mcap::ReadMessageOptions::ReadOrder::ReverseLogTimeOrder) {
+ options.startTime = 0;
+ // endTime is an exclusive range endpoint, but we want to start from `last_read_time_point_`.
+ // therefore, the time range we pass to the MCAP library is one nanosecond later than the
+ // seek point specified.
+ options.endTime = mcap::Timestamp(last_read_time_point_ + 1);
+ } else {
+ options.startTime = mcap::Timestamp(last_read_time_point_);
+ options.endTime = mcap::MaxTime;
+ }
options.readOrder = read_order_;
if (!storage_filter_.topics.empty()) {
options.topicFilter = [this](std::string_view topic) {
@@ -492,6 +504,34 @@ void MCAPStorage::reset_iterator(rcutils_time_point_value_t start_time)
linear_view_ =
std::make_unique(mcap_reader_->readMessages(OnProblem, options));
linear_iterator_ = std::make_unique(linear_view_->begin());
+ if (!read_and_enqueue_message()) {
+ return;
+ }
+ while (enqueued_message_is_already_read()) {
+ if (!read_and_enqueue_message()) {
+ return;
+ }
+ }
+}
+
+bool MCAPStorage::enqueued_message_is_already_read()
+{
+ if (last_read_message_offset_ == std::nullopt) {
+ return false;
+ }
+ if (last_enqueued_message_offset_ == std::nullopt) {
+ return false;
+ }
+ if (next_ == nullptr) {
+ return false;
+ }
+ if (last_read_time_point_ != next_->time_stamp) {
+ return false;
+ }
+ if (read_order_ == mcap::ReadMessageOptions::ReadOrder::ReverseLogTimeOrder) {
+ return (*last_enqueued_message_offset_ >= *last_read_message_offset_);
+ }
+ return (*last_enqueued_message_offset_ <= *last_read_message_offset_);
}
void MCAPStorage::ensure_summary_read()
@@ -572,6 +612,8 @@ std::shared_ptr MCAPStorage::read_next()
if (!has_next()) {
throw std::runtime_error{"No next message is available."};
}
+ last_read_time_point_ = next_->time_stamp;
+ last_read_message_offset_ = last_enqueued_message_offset_;
// Importantly, clear next_ via move so that a next message can be read.
return std::move(next_);
}
@@ -600,7 +642,11 @@ void MCAPStorage::reset_filter()
void MCAPStorage::seek(const rcutils_time_point_value_t & time_stamp)
{
- reset_iterator(time_stamp);
+ if (time_stamp != last_read_time_point_) {
+ last_read_message_offset_ = std::nullopt;
+ }
+ last_read_time_point_ = time_stamp;
+ reset_iterator();
}
/** ReadWriteInterface **/
diff --git a/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp b/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp
index c2f5665e5..046f1cd43 100644
--- a/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp
+++ b/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp
@@ -15,16 +15,9 @@
#include "rclcpp/serialization.hpp"
#include "rclcpp/serialized_message.hpp"
#include "rcpputils/filesystem_helper.hpp"
-#include "rosbag2_cpp/reader.hpp"
-#include "rosbag2_cpp/readers/sequential_reader.hpp"
-#include "rosbag2_cpp/writer.hpp"
-#include "rosbag2_cpp/writers/sequential_writer.hpp"
+#include "rosbag2_storage/storage_factory.hpp"
#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
#include "rosbag2_storage/storage_options.hpp"
-using StorageOptions = rosbag2_storage::StorageOptions;
-#else
- #include "rosbag2_cpp/storage_options.hpp"
-using StorageOptions = rosbag2_cpp::StorageOptions;
#endif
#include "rosbag2_test_common/temporary_directory_fixture.hpp"
#include "std_msgs/msg/string.hpp"
@@ -40,7 +33,7 @@ using TemporaryDirectoryFixture = rosbag2_test_common::TemporaryDirectoryFixture
TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
{
auto uri = rcpputils::fs::path(temporary_dir_path_) / "bag";
- auto expected_bag = uri / "bag_0.mcap";
+ auto expected_bag = rcpputils::fs::path(temporary_dir_path_) / "bag.mcap";
const int64_t timestamp_nanos = 100; // arbitrary value
rcutils_time_point_value_t time_stamp{timestamp_nanos};
const std::string topic_name = "test_topic";
@@ -51,9 +44,6 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
rclcpp::Serialization serialization;
{
- StorageOptions options;
- options.uri = uri.string();
- options.storage_id = storage_id;
rosbag2_storage::TopicMetadata topic_metadata;
topic_metadata.name = topic_name;
topic_metadata.type = "std_msgs/msg/String";
@@ -61,12 +51,16 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
std_msgs::msg::String msg;
msg.data = message_data;
- rosbag2_cpp::Writer writer{std::make_unique()};
-#ifndef ROSBAG2_STORAGE_MCAP_WRITER_CREATES_DIRECTORY
- rcpputils::fs::create_directories(uri);
+ rosbag2_storage::StorageFactory factory;
+#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
+ rosbag2_storage::StorageOptions options;
+ options.uri = uri.string();
+ options.storage_id = storage_id;
+ auto writer = factory.open_read_write(options);
+#else
+ auto writer = factory.open_read_write(uri.string(), storage_id);
#endif
- writer.open(options, rosbag2_cpp::ConverterOptions{});
- writer.create_topic(topic_metadata);
+ writer->create_topic(topic_metadata);
auto serialized_msg = std::make_shared();
serialization.serialize_message(&msg, serialized_msg.get());
@@ -81,20 +75,24 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
[](rcutils_uint8_array_t * /* data */) {});
serialized_bag_msg->time_stamp = time_stamp;
serialized_bag_msg->topic_name = topic_name;
- writer.write(serialized_bag_msg);
+ writer->write(serialized_bag_msg);
EXPECT_TRUE(expected_bag.is_regular_file());
}
{
- StorageOptions options;
+ rosbag2_storage::StorageFactory factory;
+#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
+ rosbag2_storage::StorageOptions options;
options.uri = expected_bag.string();
options.storage_id = storage_id;
-
- rosbag2_cpp::Reader reader{std::make_unique()};
- reader.open(options, rosbag2_cpp::ConverterOptions{});
- EXPECT_TRUE(reader.has_next());
+ auto reader = factory.open_read_only(options);
+#else
+ auto reader = factory.open_read_only(expected_bag.string(), storage_id);
+#endif
+ reader->open(options);
+ EXPECT_TRUE(reader->has_next());
std_msgs::msg::String msg;
- auto serialized_bag_msg = reader.read_next();
+ auto serialized_bag_msg = reader->read_next();
rclcpp::SerializedMessage extracted_serialized_msg(*serialized_bag_msg->serialized_data);
serialization.deserialize_message(&extracted_serialized_msg, &msg);
EXPECT_EQ(msg.data, message_data);
@@ -106,19 +104,17 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml)
{
auto uri = rcpputils::fs::path(temporary_dir_path_) / "bag";
- auto expected_bag = uri / "bag_0.mcap";
+ auto expected_bag = rcpputils::fs::path(temporary_dir_path_) / "bag.mcap";
const int64_t timestamp_nanos = 100; // arbitrary value
rcutils_time_point_value_t time_stamp{timestamp_nanos};
const std::string topic_name = "test_topic";
const std::string message_data = "Test Message 1";
const std::string storage_id = "mcap";
const std::string config_path = _TEST_RESOURCES_DIR_PATH;
- // COMPATIBILITY(foxy)
- // using verbose APIs for Foxy compatibility which did not yet provide plain-message API
rclcpp::Serialization serialization;
{
- StorageOptions options;
+ rosbag2_storage::StorageOptions options;
options.uri = uri.string();
options.storage_id = storage_id;
options.storage_config_uri = config_path + "/mcap_writer_options_zstd.yaml";
@@ -129,12 +125,9 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml)
std_msgs::msg::String msg;
msg.data = message_data;
- rosbag2_cpp::Writer writer{std::make_unique()};
- #ifndef ROSBAG2_STORAGE_MCAP_WRITER_CREATES_DIRECTORY
- rcpputils::fs::create_directories(uri);
- #endif
- writer.open(options, rosbag2_cpp::ConverterOptions{});
- writer.create_topic(topic_metadata);
+ rosbag2_storage::StorageFactory factory;
+ auto writer = factory.open_read_write(options);
+ writer->create_topic(topic_metadata);
auto serialized_msg = std::make_shared();
serialization.serialize_message(&msg, serialized_msg.get());
@@ -149,21 +142,21 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml)
[](rcutils_uint8_array_t * /* data */) {});
serialized_bag_msg->time_stamp = time_stamp;
serialized_bag_msg->topic_name = topic_name;
- writer.write(serialized_bag_msg);
- writer.write(serialized_bag_msg);
+ writer->write(serialized_bag_msg);
+ writer->write(serialized_bag_msg);
EXPECT_TRUE(expected_bag.is_regular_file());
}
{
- StorageOptions options;
+ rosbag2_storage::StorageOptions options;
options.uri = expected_bag.string();
options.storage_id = storage_id;
- rosbag2_cpp::Reader reader{std::make_unique()};
- reader.open(options, rosbag2_cpp::ConverterOptions{});
- EXPECT_TRUE(reader.has_next());
+ rosbag2_storage::StorageFactory factory;
+ auto reader = factory.open_read_only(options);
+ EXPECT_TRUE(reader->has_next());
std_msgs::msg::String msg;
- auto serialized_bag_msg = reader.read_next();
+ auto serialized_bag_msg = reader->read_next();
rclcpp::SerializedMessage extracted_serialized_msg(*serialized_bag_msg->serialized_data);
serialization.deserialize_message(&extracted_serialized_msg, &msg);
EXPECT_EQ(msg.data, message_data);
diff --git a/rosbag2_test_common/include/rosbag2_test_common/temporary_directory_fixture.hpp b/rosbag2_test_common/include/rosbag2_test_common/temporary_directory_fixture.hpp
index 97bce584e..aefb57aac 100644
--- a/rosbag2_test_common/include/rosbag2_test_common/temporary_directory_fixture.hpp
+++ b/rosbag2_test_common/include/rosbag2_test_common/temporary_directory_fixture.hpp
@@ -42,6 +42,14 @@ class TemporaryDirectoryFixture : public Test
std::string temporary_dir_path_;
};
+/**
+ * @brief parametrizes the temporary directory fixture above with a string parameter,
+ * which can be used for testing across several storage plugins.
+ */
+class ParametrizedTemporaryDirectoryFixture
+ : public TemporaryDirectoryFixture,
+ public WithParamInterface {};
+
} // namespace rosbag2_test_common
#endif // ROSBAG2_TEST_COMMON__TEMPORARY_DIRECTORY_FIXTURE_HPP_
diff --git a/rosbag2_test_common/include/rosbag2_test_common/tested_storage_ids.hpp b/rosbag2_test_common/include/rosbag2_test_common/tested_storage_ids.hpp
new file mode 100644
index 000000000..68f47baf6
--- /dev/null
+++ b/rosbag2_test_common/include/rosbag2_test_common/tested_storage_ids.hpp
@@ -0,0 +1,42 @@
+// Copyright 2022, Foxglove Technologies Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef ROSBAG2_TEST_COMMON__TESTED_STORAGE_IDS_HPP_
+#define ROSBAG2_TEST_COMMON__TESTED_STORAGE_IDS_HPP_
+#include
+#include
+
+
+namespace rosbag2_test_common
+{
+static const std::array kTestedStorageIDs = {
+ "sqlite3",
+ "mcap",
+};
+
+std::string bag_filename_for_storage_id(const std::string & name, const std::string & storage_id)
+{
+ const std::array extensions = {".db3", ".mcap"};
+ static_assert(kTestedStorageIDs.size() == extensions.size());
+ for (size_t i = 0; i < extensions.size(); ++i) {
+ if (kTestedStorageIDs[i] == storage_id) {
+ return name + extensions[i];
+ }
+ }
+ throw std::runtime_error("unknown storage id: " + storage_id);
+}
+
+} // namespace rosbag2_test_common
+
+#endif // ROSBAG2_TEST_COMMON__TESTED_STORAGE_IDS_HPP_
diff --git a/rosbag2_transport/package.xml b/rosbag2_transport/package.xml
index c3eb6c299..d91717567 100644
--- a/rosbag2_transport/package.xml
+++ b/rosbag2_transport/package.xml
@@ -29,6 +29,7 @@
rmw_implementation_cmake
rosbag2_compression_zstd
rosbag2_test_common
+ rosbag2_storage_default_plugins
test_msgs