Skip to content

Commit

Permalink
feat: add play impl (ros2#16)
Browse files Browse the repository at this point in the history
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
Signed-off-by: Jacob Bandes-Storch <jacob@foxglove.dev>
  • Loading branch information
wep21 authored and james-rms committed Nov 17, 2022
1 parent 537d28c commit 697f2bc
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 13 deletions.
2 changes: 1 addition & 1 deletion rosbag2_storage_mcap/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ include(${CMAKE_BINARY_DIR}/conan.cmake)
include(FetchContent)
fetchcontent_declare(mcap
GIT_REPOSITORY https://github.com/foxglove/mcap.git
GIT_TAG 103e8f88b00936a6ef04d9dd25c70086f3cd5c4f
GIT_TAG 3d19068feb5a78d0073e58b1cf514bad689df94a
)
fetchcontent_makeavailable(mcap)

Expand Down
25 changes: 13 additions & 12 deletions rosbag2_storage_mcap/src/mcap_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@

namespace rosbag2_storage_plugins {

using mcap::ByteOffset;
static const char FILE_EXTENSION[] = ".mcap";

/**
Expand Down Expand Up @@ -122,16 +123,13 @@ MCAPStorage::~MCAPStorage() {
/** BaseIOInterface **/
void MCAPStorage::open(const rosbag2_storage::StorageOptions& storage_options,
rosbag2_storage::storage_interfaces::IOFlag io_flag) {
relative_path_ = storage_options.uri + FILE_EXTENSION;

switch (io_flag) {
case rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY: {
relative_path_ = storage_options.uri;
input_ = std::make_unique<std::ifstream>(relative_path_, std::ios::binary);
data_source_ = std::make_unique<mcap::FileStreamReader>(*input_);
mcap_reader_ = std::make_unique<mcap::McapReader>();
mcap::McapReaderOptions options{};
options.allowFallbackScan = true;
auto status = mcap_reader_->open(*data_source_, options);
auto status = mcap_reader_->open(*data_source_);
if (!status.ok()) {
throw std::runtime_error(status.message);
}
Expand All @@ -143,6 +141,7 @@ void MCAPStorage::open(const rosbag2_storage::StorageOptions& storage_options,
case rosbag2_storage::storage_interfaces::IOFlag::APPEND: {
// APPEND does not seem to be used; treat it the same as READ_WRITE
io_flag = rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE;
relative_path_ = storage_options.uri + FILE_EXTENSION;

mcap_writer_ = std::make_unique<mcap::McapWriter>();
mcap::McapWriterOptions options{"ros2"};
Expand Down Expand Up @@ -172,21 +171,23 @@ rosbag2_storage::BagMetadata MCAPStorage::get_metadata() {
// Create a TypedRecordReader that will perform a linear scan of the MCAP file.
// This will be a fallback once index parsing is implemented in McapReader
mcap::TypedRecordReader typed_record_reader{*data_source_, 8};
typed_record_reader.onSchema = [&topic_information_schema_map,
this](const mcap::SchemaPtr schema_ptr) {
typed_record_reader.onSchema = [&topic_information_schema_map, this](
const mcap::SchemaPtr schema_ptr, ByteOffset,
std::optional<ByteOffset>) {
rosbag2_storage::TopicInformation topic_info{};
topic_info.topic_metadata.type = schema_ptr->name;
topic_info.topic_metadata.serialization_format = schema_ptr->encoding;
topic_information_schema_map.insert({schema_ptr->id, topic_info});
};
typed_record_reader.onChannel = [&topic_information_schema_map, &topic_information_channel_map](
const mcap::ChannelPtr channel_ptr) {
const mcap::ChannelPtr channel_ptr, ByteOffset,
std::optional<ByteOffset>) {
auto topic_info = topic_information_schema_map[channel_ptr->schemaId];
topic_info.topic_metadata.name = channel_ptr->topic;
topic_info.topic_metadata.serialization_format = channel_ptr->messageEncoding;
topic_information_channel_map.insert({channel_ptr->id, topic_info});
};
typed_record_reader.onStatistics = [&topic_information_channel_map,
this](const mcap::Statistics& statistics) {
typed_record_reader.onStatistics = [&topic_information_channel_map, this](
const mcap::Statistics& statistics, ByteOffset) {
metadata_.message_count = statistics.messageCount;
metadata_.duration =
std::chrono::nanoseconds(statistics.messageEndTime - statistics.messageStartTime);
Expand Down Expand Up @@ -234,7 +235,7 @@ bool MCAPStorage::read_and_enqueue_message() {
return true;
}

auto it = *linear_iterator_;
auto& it = *linear_iterator_;

// At the end of the recording
if (it == linear_view_->end()) {
Expand Down

0 comments on commit 697f2bc

Please sign in to comment.