Skip to content

Commit

Permalink
Add pause and resume service calls for rosbag2 recorder (#1131)
Browse files Browse the repository at this point in the history
* feat(recorder): Add pause and resume service calls.

Add service calls to pause recording and resume recording.

Fixes #1130

Signed-off-by: Rick Shanor <[email protected]>

* feat(recorder): pause, resume, and is_paused PR comments.

Address PR comments. Add is_paused service. Update tests accordingly.

Signed-off-by: Rick Shanor <[email protected]>

Signed-off-by: Rick Shanor <[email protected]>
  • Loading branch information
rshanor authored Nov 5, 2022
1 parent fcafa27 commit 8ebf406
Show file tree
Hide file tree
Showing 3 changed files with 65 additions and 1 deletion.
6 changes: 6 additions & 0 deletions rosbag2_transport/include/rosbag2_transport/recorder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@

#include "rosbag2_cpp/writer.hpp"

#include "rosbag2_interfaces/srv/is_paused.hpp"
#include "rosbag2_interfaces/srv/pause.hpp"
#include "rosbag2_interfaces/srv/resume.hpp"
#include "rosbag2_interfaces/srv/snapshot.hpp"
#include "rosbag2_interfaces/srv/split_bagfile.hpp"

Expand Down Expand Up @@ -158,6 +161,9 @@ class Recorder : public rclcpp::Node
std::string serialization_format_;
std::unordered_map<std::string, rclcpp::QoS> topic_qos_profile_overrides_;
std::unordered_set<std::string> topic_unknown_types_;
rclcpp::Service<rosbag2_interfaces::srv::IsPaused>::SharedPtr srv_is_paused_;
rclcpp::Service<rosbag2_interfaces::srv::Pause>::SharedPtr srv_pause_;
rclcpp::Service<rosbag2_interfaces::srv::Resume>::SharedPtr srv_resume_;
rclcpp::Service<rosbag2_interfaces::srv::Snapshot>::SharedPtr srv_snapshot_;
rclcpp::Service<rosbag2_interfaces::srv::SplitBagfile>::SharedPtr srv_split_bagfile_;
std::atomic<bool> paused_ = false;
Expand Down
30 changes: 30 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,36 @@ void Recorder::record()
writer_->split_bagfile();
});

srv_pause_ = create_service<rosbag2_interfaces::srv::Pause>(
"~/pause",
[this](
const std::shared_ptr<rmw_request_id_t>/* request_header */,
const std::shared_ptr<rosbag2_interfaces::srv::Pause::Request>/* request */,
const std::shared_ptr<rosbag2_interfaces::srv::Pause::Response>/* response */)
{
pause();
});

srv_resume_ = create_service<rosbag2_interfaces::srv::Resume>(
"~/resume",
[this](
const std::shared_ptr<rmw_request_id_t>/* request_header */,
const std::shared_ptr<rosbag2_interfaces::srv::Resume::Request>/* request */,
const std::shared_ptr<rosbag2_interfaces::srv::Resume::Response>/* response */)
{
resume();
});

srv_is_paused_ = create_service<rosbag2_interfaces::srv::IsPaused>(
"~/is_paused",
[this](
const std::shared_ptr<rmw_request_id_t>/* request_header */,
const std::shared_ptr<rosbag2_interfaces::srv::IsPaused::Request>/* request */,
const std::shared_ptr<rosbag2_interfaces::srv::IsPaused::Response> response)
{
response->paused = is_paused();
});

// 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 @@ -21,6 +21,9 @@

#include "rclcpp/rclcpp.hpp"

#include "rosbag2_interfaces/srv/is_paused.hpp"
#include "rosbag2_interfaces/srv/pause.hpp"
#include "rosbag2_interfaces/srv/resume.hpp"
#include "rosbag2_interfaces/srv/snapshot.hpp"
#include "rosbag2_interfaces/srv/split_bagfile.hpp"
#include "rosbag2_transport/recorder.hpp"
Expand All @@ -36,6 +39,9 @@ using namespace ::testing; // NOLINT
class RecordSrvsTest : public RecordIntegrationTestFixture
{
public:
using IsPaused = rosbag2_interfaces::srv::IsPaused;
using Pause = rosbag2_interfaces::srv::Pause;
using Resume = rosbag2_interfaces::srv::Resume;
using Snapshot = rosbag2_interfaces::srv::Snapshot;
using SplitBagfile = rosbag2_interfaces::srv::SplitBagfile;

Expand Down Expand Up @@ -74,9 +80,11 @@ class RecordSrvsTest : public RecordIntegrationTestFixture
pub_manager.setup_publisher(test_topic_, string_message, 10);

const std::string ns = "/" + recorder_name_;
cli_is_paused_ = client_node_->create_client<IsPaused>(ns + "/is_paused");
cli_pause_ = client_node_->create_client<Pause>(ns + "/pause");
cli_resume_ = client_node_->create_client<Resume>(ns + "/resume");
cli_snapshot_ = client_node_->create_client<Snapshot>(ns + "/snapshot");
cli_split_bagfile_ = client_node_->create_client<SplitBagfile>(ns + "/split_bagfile");

exec_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

exec_->add_node(recorder_);
Expand Down Expand Up @@ -133,6 +141,9 @@ class RecordSrvsTest : public RecordIntegrationTestFixture

// Service clients
rclcpp::Node::SharedPtr client_node_;
rclcpp::Client<IsPaused>::SharedPtr cli_is_paused_;
rclcpp::Client<Pause>::SharedPtr cli_pause_;
rclcpp::Client<Resume>::SharedPtr cli_resume_;
rclcpp::Client<Snapshot>::SharedPtr cli_snapshot_;
rclcpp::Client<SplitBagfile>::SharedPtr cli_split_bagfile_;

Expand Down Expand Up @@ -198,3 +209,20 @@ TEST_F(RecordSrvsTest, split_bagfile)
EXPECT_EQ(closed_file, "BagFile0");
EXPECT_EQ(opened_file, "BagFile1");
}

TEST_F(RecordSrvsTest, pause_resume)
{
EXPECT_FALSE(recorder_->is_paused());
auto is_paused_response = successful_service_request<IsPaused>(cli_is_paused_);
EXPECT_FALSE(is_paused_response->paused);

successful_service_request<Pause>(cli_pause_);
EXPECT_TRUE(recorder_->is_paused());
is_paused_response = successful_service_request<IsPaused>(cli_is_paused_);
EXPECT_TRUE(is_paused_response->paused);

successful_service_request<Resume>(cli_resume_);
EXPECT_FALSE(recorder_->is_paused());
is_paused_response = successful_service_request<IsPaused>(cli_is_paused_);
EXPECT_FALSE(is_paused_response->paused);
}

0 comments on commit 8ebf406

Please sign in to comment.