Skip to content

Commit 02a70b4

Browse files
authored
Implement storing and loading ROS_DISTRO from metadata.yaml and mcap files (#1241)
* Implement storing and loading ROS_DISTRO from mcap metadata Signed-off-by: Emerson Knapp <[email protected]> * Just add ros_distro to BagMetadata and skip all the side channeling, why do that Signed-off-by: Emerson Knapp <[email protected]> * Fix functionality Signed-off-by: Emerson Knapp <[email protected]> * Add mcap test Signed-off-by: Emerson Knapp <[email protected]> * Move functions to get_metadata and update_metadata Signed-off-by: Emerson Knapp <[email protected]> * Update metadata version Signed-off-by: Emerson Knapp <[email protected]> * Add warning message when ROS_DISTRO not set Signed-off-by: Emerson Knapp <[email protected]> * Small tweaks Signed-off-by: Emerson Knapp <[email protected]> * Update test expectation and print unknown when value unknown Signed-off-by: Emerson Knapp <[email protected]> * comment out unused variable Signed-off-by: Emerson Knapp <[email protected]> --------- Signed-off-by: Emerson Knapp <[email protected]>
1 parent 13f5151 commit 02a70b4

File tree

11 files changed

+76
-31
lines changed

11 files changed

+76
-31
lines changed

rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include <utility>
2525
#include <vector>
2626

27+
#include "rcpputils/env.hpp"
2728
#include "rcpputils/filesystem_helper.hpp"
2829

2930
#include "rosbag2_cpp/info.hpp"
@@ -78,6 +79,11 @@ void SequentialWriter::init_metadata()
7879
file_info.message_count = 0;
7980
metadata_.custom_data = storage_options_.custom_data;
8081
metadata_.files = {file_info};
82+
metadata_.ros_distro = rcpputils::get_env_var("ROS_DISTRO");
83+
if (metadata_.ros_distro.empty()) {
84+
ROSBAG2_CPP_LOG_WARN(
85+
"Environment variable ROS_DISTRO not set, can't store value in bag metadata.");
86+
}
8187
}
8288

8389
void SequentialWriter::open(

rosbag2_py/src/rosbag2_py/_storage.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -229,7 +229,8 @@ PYBIND11_MODULE(_storage, m) {
229229
std::vector<rosbag2_storage::TopicInformation> topics_with_message_count,
230230
std::string compression_format,
231231
std::string compression_mode,
232-
std::unordered_map<std::string, std::string> custom_data)
232+
std::unordered_map<std::string, std::string> custom_data,
233+
std::string ros_distro)
233234
{
234235
return rosbag2_storage::BagMetadata{
235236
version,
@@ -243,10 +244,11 @@ PYBIND11_MODULE(_storage, m) {
243244
topics_with_message_count,
244245
compression_format,
245246
compression_mode,
246-
custom_data
247+
custom_data,
248+
ros_distro,
247249
};
248250
}),
249-
pybind11::arg("version") = 7,
251+
pybind11::arg("version") = rosbag2_storage::BagMetadata{}.version,
250252
pybind11::arg("bag_size") = 0,
251253
pybind11::arg("storage_identifier") = "",
252254
pybind11::arg("relative_file_paths") = std::vector<std::string>(),
@@ -258,7 +260,8 @@ PYBIND11_MODULE(_storage, m) {
258260
pybind11::arg("topics_with_message_count") = std::vector<rosbag2_storage::TopicInformation>(),
259261
pybind11::arg("compression_format") = "",
260262
pybind11::arg("compression_mode") = "",
261-
pybind11::arg("custom_data") = std::unordered_map<std::string, std::string>())
263+
pybind11::arg("custom_data") = std::unordered_map<std::string, std::string>(),
264+
pybind11::arg("ros_distro") = "")
262265
.def_readwrite("version", &rosbag2_storage::BagMetadata::version)
263266
.def_readwrite("bag_size", &rosbag2_storage::BagMetadata::bag_size)
264267
.def_readwrite("storage_identifier", &rosbag2_storage::BagMetadata::storage_identifier)
@@ -287,6 +290,7 @@ PYBIND11_MODULE(_storage, m) {
287290
.def_readwrite("compression_format", &rosbag2_storage::BagMetadata::compression_format)
288291
.def_readwrite("compression_mode", &rosbag2_storage::BagMetadata::compression_mode)
289292
.def_readwrite("custom_data", &rosbag2_storage::BagMetadata::custom_data)
293+
.def_readwrite("ros_distro", &rosbag2_storage::BagMetadata::ros_distro)
290294
.def(
291295
"__repr__", [](const rosbag2_storage::BagMetadata & metadata) {
292296
return format_bag_meta_data(metadata);

rosbag2_py/src/rosbag2_py/format_bag_metadata.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -140,13 +140,18 @@ std::string format_bag_meta_data(const rosbag2_storage::BagMetadata & metadata)
140140
auto end_time = start_time + metadata.duration;
141141
std::stringstream info_stream;
142142
int indentation_spaces = 19; // The longest info field (Topics with Type:) plus one space.
143+
std::string ros_distro = metadata.ros_distro;
144+
if (ros_distro.empty()) {
145+
ros_distro = "unknown";
146+
}
143147

144148
info_stream << std::endl;
145149
info_stream << "Files: ";
146150
format_file_paths(metadata.relative_file_paths, info_stream, indentation_spaces);
147151
info_stream << "Bag size: " << format_file_size(
148152
metadata.bag_size) << std::endl;
149153
info_stream << "Storage id: " << metadata.storage_identifier << std::endl;
154+
info_stream << "ROS Distro: " << ros_distro << std::endl;
150155
info_stream << "Duration: " << format_duration(
151156
metadata.duration)["time_in_sec"] << "s" << std::endl;
152157
info_stream << "Start: " << format_time_point(start_time) <<

rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ struct FileInformation
4242

4343
struct BagMetadata
4444
{
45-
int version = 7; // upgrade this number when changing the content of the struct
45+
int version = 8; // upgrade this number when changing the content of the struct
4646
uint64_t bag_size = 0; // Will not be serialized
4747
std::string storage_identifier;
4848
std::vector<std::string> relative_file_paths;
@@ -54,6 +54,7 @@ struct BagMetadata
5454
std::string compression_format;
5555
std::string compression_mode;
5656
std::unordered_map<std::string, std::string> custom_data; // {key: value, ...}
57+
std::string ros_distro;
5758
};
5859

5960
} // namespace rosbag2_storage

rosbag2_storage/include/rosbag2_storage/yaml.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -243,7 +243,7 @@ struct convert<rosbag2_storage::BagMetadata>
243243
node["relative_file_paths"] = metadata.relative_file_paths;
244244
node["files"] = metadata.files;
245245
node["custom_data"] = metadata.custom_data;
246-
246+
node["ros_distro"] = metadata.ros_distro;
247247
return node;
248248
}
249249

@@ -273,7 +273,9 @@ struct convert<rosbag2_storage::BagMetadata>
273273
if (metadata.version >= 6) {
274274
metadata.custom_data = node["custom_data"].as<std::unordered_map<std::string, std::string>>();
275275
}
276-
276+
if (metadata.version >= 8) {
277+
metadata.ros_distro = node["ros_distro"].as<std::string>();
278+
}
277279
return true;
278280
}
279281
};

rosbag2_storage_mcap/src/mcap_storage.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -424,6 +424,31 @@ rosbag2_storage::BagMetadata MCAPStorage::get_metadata()
424424
metadata_.topics_with_message_count.push_back(topic_info);
425425
}
426426

427+
const auto & mcap_metadatas = mcap_reader_->metadataIndexes();
428+
auto range = mcap_metadatas.equal_range("rosbag2");
429+
mcap::Status status{};
430+
mcap::Record mcap_record{};
431+
mcap::Metadata mcap_metadata{};
432+
for (auto i = range.first; i != range.second; ++i) {
433+
status = mcap::McapReader::ReadRecord(*data_source_, i->second.offset, &mcap_record);
434+
if (!status.ok()) {
435+
OnProblem(status);
436+
continue;
437+
}
438+
status = mcap::McapReader::ParseMetadata(mcap_record, &mcap_metadata);
439+
if (!status.ok()) {
440+
OnProblem(status);
441+
continue;
442+
}
443+
try {
444+
metadata_.ros_distro = mcap_metadata.metadata.at("ROS_DISTRO");
445+
} catch (const std::out_of_range & /* err */) {
446+
RCUTILS_LOG_ERROR_NAMED(
447+
LOG_NAME, "Metadata record with name 'rosbag2' did not contain key 'ROS_DISTRO'.");
448+
}
449+
break;
450+
}
451+
427452
return metadata_;
428453
}
429454

@@ -803,6 +828,14 @@ void MCAPStorage::update_metadata(const rosbag2_storage::BagMetadata & bag_metad
803828
"MCAP storage plugin does not support message compression, "
804829
"consider using chunk compression by setting `compression: 'Zstd'` in storage config");
805830
}
831+
832+
mcap::Metadata metadata;
833+
metadata.name = "rosbag2";
834+
metadata.metadata = {{"ROS_DISTRO", bag_metadata.ros_distro}};
835+
mcap::Status status = mcap_writer_->write(metadata);
836+
if (!status.ok()) {
837+
OnProblem(status);
838+
}
806839
}
807840
#endif
808841

rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
#include "rclcpp/serialization.hpp"
1616
#include "rclcpp/serialized_message.hpp"
17+
#include "rcpputils/env.hpp"
1718
#include "rcpputils/filesystem_helper.hpp"
1819
#include "rosbag2_storage/storage_factory.hpp"
1920
#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
@@ -52,6 +53,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
5253
// COMPATIBILITY(foxy)
5354
// using verbose APIs for Foxy compatibility which did not yet provide plain-message API
5455
rclcpp::Serialization<std_msgs::msg::String> serialization;
56+
rosbag2_storage::StorageFactory factory;
5557

5658
{
5759
rosbag2_storage::TopicMetadata topic_metadata;
@@ -64,7 +66,6 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
6466
std_msgs::msg::String msg;
6567
msg.data = message_data;
6668

67-
rosbag2_storage::StorageFactory factory;
6869
#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
6970
rosbag2_storage::StorageOptions options;
7071
options.uri = uri.string();
@@ -89,10 +90,9 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
8990
serialized_bag_msg->time_stamp = time_stamp;
9091
serialized_bag_msg->topic_name = topic_name;
9192
writer->write(serialized_bag_msg);
92-
EXPECT_TRUE(expected_bag.is_regular_file());
9393
}
94+
EXPECT_TRUE(expected_bag.is_regular_file());
9495
{
95-
rosbag2_storage::StorageFactory factory;
9696
#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
9797
rosbag2_storage::StorageOptions options;
9898
options.uri = expected_bag.string();
@@ -118,6 +118,9 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
118118
1u}}));
119119
EXPECT_THAT(metadata.message_count, Eq(1u));
120120

121+
const auto current_distro = rcpputils::get_env_var("ROS_DISTRO");
122+
EXPECT_EQ(metadata.ros_distro, current_distro);
123+
121124
EXPECT_TRUE(reader->has_next());
122125

123126
std_msgs::msg::String msg;

rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_storage.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,6 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage
105105
SqliteWrapper & get_sqlite_database_wrapper();
106106

107107
int get_db_schema_version() const;
108-
std::string get_recorded_ros_distro() const;
109108

110109
enum class PresetProfile
111110
{

rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -751,6 +751,13 @@ void SqliteStorage::read_metadata()
751751
std::chrono::time_point<std::chrono::high_resolution_clock>(std::chrono::nanoseconds(min_time));
752752
metadata_.duration = std::chrono::nanoseconds(max_time) - std::chrono::nanoseconds(min_time);
753753
metadata_.bag_size = get_bagfile_size();
754+
755+
if (db_schema_version_ >= 3 && database_->table_exists("schema")) {
756+
// Read schema version
757+
auto statement = database_->prepare_statement("SELECT ros_distro from schema;");
758+
auto query_results = statement->execute_query<std::string>();
759+
metadata_.ros_distro = std::get<0>(*query_results.begin());
760+
}
754761
}
755762

756763
rosbag2_storage::BagMetadata SqliteStorage::get_metadata()
@@ -802,18 +809,6 @@ int SqliteStorage::get_db_schema_version() const
802809
return db_schema_version_;
803810
}
804811

805-
std::string SqliteStorage::get_recorded_ros_distro() const
806-
{
807-
std::string ros_distro;
808-
if (db_schema_version_ >= 3 && database_->table_exists("schema")) {
809-
// Read schema version
810-
auto statement = database_->prepare_statement("SELECT ros_distro from schema;");
811-
auto query_results = statement->execute_query<std::string>();
812-
ros_distro = std::get<0>(*query_results.begin());
813-
}
814-
return ros_distro;
815-
}
816-
817812
int SqliteStorage::get_last_rowid()
818813
{
819814
auto statement = database_->prepare_statement("SELECT max(rowid) from messages;");

rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp

Lines changed: 3 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -350,15 +350,13 @@ TEST_F(StorageTestFixture, get_db_schema_version_returns_correct_value) {
350350
EXPECT_GE(writable_storage->get_db_schema_version(), 3);
351351
}
352352

353-
TEST_F(StorageTestFixture, get_recorded_ros_distro_returns_correct_value) {
353+
TEST_F(StorageTestFixture, metadata_ros_distro_returns_correct_value) {
354354
auto writable_storage = std::make_shared<rosbag2_storage_plugins::SqliteStorage>();
355-
EXPECT_TRUE(writable_storage->get_recorded_ros_distro().empty());
356-
357355
auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string();
358356
writable_storage->open({db_file, plugin_id_});
359357

360358
std::string current_ros_distro = rcpputils::get_env_var("ROS_DISTRO");
361-
EXPECT_EQ(writable_storage->get_recorded_ros_distro(), current_ros_distro);
359+
EXPECT_EQ(writable_storage->get_metadata().ros_distro, current_ros_distro);
362360
}
363361

364362
TEST_F(StorageTestFixture, check_backward_compatibility_with_schema_version_2) {
@@ -367,17 +365,14 @@ TEST_F(StorageTestFixture, check_backward_compatibility_with_schema_version_2) {
367365
std::make_unique<rosbag2_storage_plugins::SqliteStorage>();
368366

369367
EXPECT_EQ(readable_storage->get_db_schema_version(), -1);
370-
EXPECT_TRUE(readable_storage->get_recorded_ros_distro().empty());
371368

372369
auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string();
373-
374370
readable_storage->open(
375371
{db_file, plugin_id_},
376372
rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY);
377-
std::vector<std::shared_ptr<rosbag2_storage::SerializedBagMessage>> read_messages;
378373

379374
EXPECT_EQ(readable_storage->get_db_schema_version(), 2);
380-
EXPECT_TRUE(readable_storage->get_recorded_ros_distro().empty());
375+
EXPECT_TRUE(readable_storage->get_metadata().ros_distro.empty());
381376
}
382377

383378
TEST_F(StorageTestFixture, get_metadata_returns_correct_struct_if_no_messages) {

0 commit comments

Comments
 (0)