Skip to content

Commit

Permalink
feat(rosbag2_cpp): Add SplitBagfile recording service.
Browse files Browse the repository at this point in the history
Fixes #1087

Tested from the command line and verified that below command closed one
log file and opened another

ros2 service call /rosbag2_recorder/split_bagfile
rosbag2_interfaces/srv/SplitBagfile

Signed-off-by: Rick Shanor <rickshanor@gmail.com>
  • Loading branch information
rshanor committed Oct 5, 2022
1 parent c92010b commit 5e5679e
Show file tree
Hide file tree
Showing 9 changed files with 37 additions and 1 deletion.
5 changes: 5 additions & 0 deletions rosbag2_cpp/include/rosbag2_cpp/writer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,11 @@ class ROSBAG2_CPP_PUBLIC Writer final
*/
bool take_snapshot();

/**
* Close the current bagfile and opens the next bagfile.
*/
void split_bagfile();

/**
* Remove a new topic in the underlying storage.
* If creation of subscription fails remove the topic
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,11 @@ class ROSBAG2_CPP_PUBLIC BaseWriterInterface
*/
virtual bool take_snapshot() = 0;

/**
* Close the current bagfile and opens the next bagfile.
*/
virtual void split_bagfile() = 0;

virtual void add_event_callbacks(const bag_events::WriterEventCallbacks & callbacks) = 0;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ class ROSBAG2_CPP_PUBLIC SequentialWriter
rosbag2_storage::BagMetadata metadata_;

// Closes the current backed storage and opens the next bagfile.
virtual void split_bagfile();
void split_bagfile() override;

// Checks if the current recording bagfile needs to be split and rolled over to a new file.
bool should_split_bagfile(
Expand Down
6 changes: 6 additions & 0 deletions rosbag2_cpp/src/rosbag2_cpp/writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,12 @@ bool Writer::take_snapshot()
return writer_impl_->take_snapshot();
}

void Writer::split_bagfile()
{
std::lock_guard<std::mutex> writer_lock(writer_mutex_);
return writer_impl_->split_bagfile();
}

void Writer::write(std::shared_ptr<const rosbag2_storage::SerializedBagMessage> message)
{
std::lock_guard<std::mutex> writer_lock(writer_mutex_);
Expand Down
1 change: 1 addition & 0 deletions rosbag2_interfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"srv/Seek.srv"
"srv/SetRate.srv"
"srv/Snapshot.srv"
"srv/SplitBagfile.srv"
"srv/Stop.srv"
"srv/TogglePaused.srv"
DEPENDENCIES builtin_interfaces
Expand Down
1 change: 1 addition & 0 deletions rosbag2_interfaces/srv/SplitBagfile.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
---
2 changes: 2 additions & 0 deletions rosbag2_transport/include/rosbag2_transport/recorder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include "rosbag2_cpp/writer.hpp"

#include "rosbag2_interfaces/srv/snapshot.hpp"
#include "rosbag2_interfaces/srv/split_bagfile.hpp"

#include "rosbag2_interfaces/msg/write_split_event.hpp"

Expand Down Expand Up @@ -158,6 +159,7 @@ class Recorder : public rclcpp::Node
std::unordered_map<std::string, rclcpp::QoS> topic_qos_profile_overrides_;
std::unordered_set<std::string> topic_unknown_types_;
rclcpp::Service<rosbag2_interfaces::srv::Snapshot>::SharedPtr srv_snapshot_;
rclcpp::Service<rosbag2_interfaces::srv::SplitBagfile>::SharedPtr srv_split_bagfile_;
std::atomic<bool> paused_ = false;
// Keyboard handler
std::shared_ptr<KeyboardHandler> keyboard_handler_;
Expand Down
10 changes: 10 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,16 @@ void Recorder::record()
});
}

srv_split_bagfile_ = create_service<rosbag2_interfaces::srv::SplitBagfile>(
"~/split_bagfile",
[this](
const std::shared_ptr<rmw_request_id_t>/* request_header */,
const std::shared_ptr<rosbag2_interfaces::srv::SplitBagfile::Request>,
const std::shared_ptr<rosbag2_interfaces::srv::SplitBagfile::Response> response)
{
writer_->split_bagfile();
});

// Start the thread that will publish events
event_publisher_thread_ = std::thread(&Recorder::event_publisher_thread_main, this);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,12 @@ class MockSequentialWriter : public rosbag2_cpp::writer_interfaces::BaseWriterIn
return true;
}

void split_bagfile() override
{
auto info = std::make_shared<rosbag2_cpp::bag_events::BagSplitInfo>();
callback_manager_.execute_callbacks(rosbag2_cpp::bag_events::BagEvent::WRITE_SPLIT, info);
}

void
add_event_callbacks(const rosbag2_cpp::bag_events::WriterEventCallbacks & callbacks) override
{
Expand Down

0 comments on commit 5e5679e

Please sign in to comment.