Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add MCAP support to offline node #67

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 7 additions & 1 deletion cartographer_ros/src/playable_bag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "tf2_msgs/msg/tf_message.hpp"
#include "rosbag2_storage/topic_metadata.hpp"
#include "rosbag2_storage/bag_metadata.hpp"
#include <filesystem>

namespace cartographer_ros {

Expand All @@ -38,7 +39,12 @@ PlayableBag::PlayableBag(
filtering_early_message_handler_(
std::move(filtering_early_message_handler)) {
LOG(WARNING) << "Opening bag: " << bag_filename;
bag_reader_->open(bag_filename);
if (std::filesystem::path(bag_filename).extension() == ".mcap") {
bag_reader_->open(rosbag2_storage::StorageOptions{bag_filename,"mcap"},
rosbag2_cpp::ConverterOptions{"cdr", "cdr"});
} else {
bag_reader_->open(bag_filename);
}
Comment on lines +42 to +47

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hm, shouldn't the rosbag2 API be figuring this out for us? If we have to do this, I consider it a problem with that API and we should fix it there.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I simply followed the rosbag2_cpp open function documentation which explicitly states that it assumes sqlite3 storage backend when using the path only overload:
https://github.com/ros2/rosbag2/blob/0c7c352222a08470211232453dab9749ab405201/rosbag2_cpp/include/rosbag2_cpp/reader.hpp#L64-L78

/**

  • Opens an existing bagfile and prepare it for reading messages.
  • The bagfile must exist.
  • This must be called before any other function is used.
  • \note This will open URI with the default storage options
    • using sqlite3 storage backend
    • using no converter options, storing messages with the incoming serialization format
  • \sa rmw_get_serialization_format.
  • For specifications, please see \sa open, which let's you specify
  • more storage and converter options.
  • \param storage_uri URI of the storage to open.
    **/
    void open(const std::string & uri);

And the Foxglove documentation which says to specify the StorageOptions and ConverterOptions (for python):

Reading from MCAP

The rosbag2_storage_mcap plugin works seamlessly with the existing rosbag2_py API for reading messages out of bags, so your rosbag2 scripts will continue to work with minimal changes. Just specify “mcap” as your storage ID when opening a bag file:

reader.open(
rosbag2_py.StorageOptions(uri=input_bag, storage_id="mcap"),
rosbag2_py.ConverterOptions(
input_serialization_format="cdr", output_serialization_format="cdr"
),
)

Without thinking much.
But if you think we can add automatic detection of the mcap storage_id based of the file extension directly in the rosbag2 API, I will happily do a PR (for the cpp part)

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Note that a manual flag has to be used for ros2 bag play usage with MCAP too:

$ ros2 bag play -s mcap path/to/your_recording.mcap

bag_metadata = bag_reader_->get_metadata();
duration_in_seconds_ = bag_metadata.duration.count()/1e9;
LOG(WARNING) << "duration_in_seconds_: " << duration_in_seconds_;
Expand Down