Skip to content

Commit

Permalink
[iron] Add ROS_DISTRO metadata record to mcap file when opening for w…
Browse files Browse the repository at this point in the history
…riting (#1371)

* Iron: Add ROS_DISTRO metadata record to mcap file when opening for writing

Signed-off-by: Emerson Knapp <[email protected]>
  • Loading branch information
emersonknapp authored Jun 12, 2023
1 parent 2934b59 commit 33edccf
Show file tree
Hide file tree
Showing 3 changed files with 61 additions and 0 deletions.
1 change: 1 addition & 0 deletions rosbag2_storage_mcap/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,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}
mcap_vendor::mcap
rosbag2_storage::rosbag2_storage
rosbag2_test_common::rosbag2_test_common
${std_msgs_TARGETS}
Expand Down
19 changes: 19 additions & 0 deletions rosbag2_storage_mcap/src/mcap_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "rcpputils/env.hpp"
#include "rcutils/logging_macros.h"
#include "rosbag2_storage/metadata_io.hpp"
#include "rosbag2_storage/ros_helper.hpp"
Expand Down Expand Up @@ -237,6 +238,7 @@ class ROSBAG2_STORAGE_MCAP_PUBLIC MCAPStorage
bool enqueued_message_is_already_read();
bool message_indexes_present();
void ensure_summary_read();
void ensure_rosdistro_metadata_added();

std::optional<rosbag2_storage::storage_interfaces::IOFlag> opened_as_;
std::string relative_path_;
Expand All @@ -259,6 +261,7 @@ class ROSBAG2_STORAGE_MCAP_PUBLIC MCAPStorage
std::unique_ptr<mcap::McapWriter> mcap_writer_;

bool has_read_summary_ = false;
bool has_added_ros_distro_metadata_ = false;
rcutils_time_point_value_t last_read_time_point_ = 0;
std::optional<mcap::RecordOffset> last_read_message_offset_;
std::optional<mcap::RecordOffset> last_enqueued_message_offset_;
Expand Down Expand Up @@ -363,6 +366,7 @@ void MCAPStorage::open_impl(const std::string & uri, const std::string & preset_
if (!status.ok()) {
throw std::runtime_error(status.message);
}
ensure_rosdistro_metadata_added();
break;
}
}
Expand Down Expand Up @@ -803,9 +807,24 @@ void MCAPStorage::update_metadata(const rosbag2_storage::BagMetadata & bag_metad
"MCAP storage plugin does not support message compression, "
"consider using chunk compression by setting `compression: 'Zstd'` in storage config");
}
ensure_rosdistro_metadata_added();
}
#endif

void MCAPStorage::ensure_rosdistro_metadata_added()
{
if (!has_added_ros_distro_metadata_) {
mcap::Metadata metadata;
metadata.name = "rosbag2";
metadata.metadata = {{"ROS_DISTRO", rcpputils::get_env_var("ROS_DISTRO")}};
mcap::Status status = mcap_writer_->write(metadata);
if (!status.ok()) {
OnProblem(status);
}
}
has_added_ros_distro_metadata_ = true;
}

} // namespace rosbag2_storage_plugins

#include "pluginlib/class_list_macros.hpp" // NOLINT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include "rclcpp/serialization.hpp"
#include "rclcpp/serialized_message.hpp"
#include "rcpputils/env.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "rosbag2_storage/storage_factory.hpp"
#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
Expand All @@ -22,6 +23,8 @@
#include "rosbag2_test_common/temporary_directory_fixture.hpp"
#include "std_msgs/msg/string.hpp"

#include <mcap/mcap.hpp>

#include <gmock/gmock.h>

#include <memory>
Expand Down Expand Up @@ -200,3 +203,41 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml)
}
}
#endif // #ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS

TEST_F(TemporaryDirectoryFixture, mcap_contains_ros_distro)
{
// Guarantee env var set for mcap to use - in a full-build testing environment it may not be.
const std::string current_ros_distro = "rolling";
ASSERT_TRUE(rcpputils::set_env_var("ROS_DISTRO", current_ros_distro.c_str()));

const auto expected_file = rcpputils::fs::path(temporary_dir_path_) / "rosdistro_bag.mcap";
const auto uri = rcpputils::fs::remove_extension(expected_file);
const std::string storage_id = "mcap";
std::string read_metadata_ros_distro = "";

// Open writer to create no-data file and then delete the writer to close
rosbag2_storage::StorageFactory factory;
rosbag2_storage::StorageOptions options;
options.uri = uri.string();
options.storage_id = storage_id;
auto writer = factory.open_read_write(options);
writer.reset();
ASSERT_TRUE(expected_file.is_regular_file());

// Open created mcap file, read all metadata records to find rosbag2.ROS_DISTRO value
mcap::Status status{};
std::ifstream input{expected_file.string(), std::ios::binary};
mcap::FileStreamReader data_source{input};
mcap::TypedRecordReader typed_reader(data_source, 8);
bool done = false;
typed_reader.onMetadata = [&](const mcap::Metadata & metadata, mcap::ByteOffset) {
if (metadata.name == "rosbag2") {
read_metadata_ros_distro = metadata.metadata.at("ROS_DISTRO");
done = true;
}
};
while (!done && typed_reader.next()) {
EXPECT_TRUE(typed_reader.status().ok());
}
EXPECT_EQ(read_metadata_ros_distro, current_ros_distro);
}

0 comments on commit 33edccf

Please sign in to comment.