Skip to content

Commit

Permalink
Add service to stop recording - Set bag name when recording is started (
Browse files Browse the repository at this point in the history
#6)

Added feature: add service to stop recording
---------

Signed-off-by: Beniamino Pozzan <b.pozzan@archangel.im>
Co-authored-by: Bernd Pfrommer <bernd.pfrommer@gmail.com>
  • Loading branch information
beniaminopozzan and berndpfrommer authored Jan 2, 2025
1 parent 9c6eb56 commit b398a6b
Show file tree
Hide file tree
Showing 3 changed files with 59 additions and 11 deletions.
10 changes: 8 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,17 @@ Alternatively, use the python script:
```
ros2 run rosbag2_composable_recorder start_recording.py
```
To stop the recording you have to kill (Ctrl-C) the recording driver.
To stop the recording, either kill (Ctrl-C) the recording driver or call the stop service:
```
ros2 service call /stop_recording std_srvs/srv/Trigger
```

## Parameters

- ``bag_name``: (default: empty) prefix of directory name used for bag.
- ``bag_name``: (default: empty) prefix of directory name used for
bag. Note: if you stop the recording and restart, the recorder node
will throw an exception and exit because the bag already
exists. Use ``bag_prefix`` in this case.
- ``bag_prefix``: (default: ``rosbag_2``) prefix of directory name used for storage. A
timestamp will be appended. This parameter is only used when no
``bag_name`` is specified.
Expand Down
9 changes: 8 additions & 1 deletion include/rosbag2_composable_recorder/composable_recorder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,16 @@ class ComposableRecorder : public rosbag2_transport::Recorder
const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
std::shared_ptr<std_srvs::srv::Trigger::Response> res);

bool stopRecording(
const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
std::shared_ptr<std_srvs::srv::Trigger::Response> res);

// ---- variables
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr start_service_;
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr stop_service_;
bool isRecording_{false};
std::string bag_name_;
std::string bag_prefix_;
};

} // namespace rosbag2_composable_recorder
Expand Down
51 changes: 43 additions & 8 deletions src/composable_recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,9 @@ ComposableRecorder::ComposableRecorder(const rclcpp::NodeOptions & options)
: rosbag2_transport::Recorder(
std::make_shared<rosbag2_cpp::Writer>(), rosbag2_storage::StorageOptions(),
rosbag2_transport::RecordOptions(), "recorder",
rclcpp::NodeOptions(options).start_parameter_event_publisher(false))
rclcpp::NodeOptions(options).start_parameter_event_publisher(false)),
bag_name_(declare_parameter<std::string>("bag_name", "")),
bag_prefix_(declare_parameter<std::string>("bag_prefix", "rosbag2_"))
{
std::vector<std::string> topics =
declare_parameter<std::vector<std::string>>("topics", std::vector<std::string>());
Expand All @@ -52,12 +54,6 @@ ComposableRecorder::ComposableRecorder(const rclcpp::NodeOptions & options)
#endif
sopt.storage_id = declare_parameter<std::string>("storage_id", "sqlite3");
sopt.max_cache_size = declare_parameter<int>("max_cache_size", 100 * 1024 * 1024);
const std::string bag_name = declare_parameter<std::string>("bag_name", "");
if (!bag_name.empty()) {
sopt.uri = bag_name;
} else {
sopt.uri = declare_parameter<std::string>("bag_prefix", "rosbag2_") + get_time_stamp();
}

// set recorder options
#ifdef USE_GET_RECORD_OPTIONS
Expand Down Expand Up @@ -86,11 +82,15 @@ ComposableRecorder::ComposableRecorder(const rclcpp::NodeOptions & options)
if (declare_parameter<bool>("start_recording_immediately", false)) {
record();
} else {
service_ = create_service<std_srvs::srv::Trigger>(
start_service_ = create_service<std_srvs::srv::Trigger>(
"start_recording",
std::bind(
&ComposableRecorder::startRecording, this, std::placeholders::_1, std::placeholders::_2));
}
stop_service_ = create_service<std_srvs::srv::Trigger>(
"stop_recording",
std::bind(
&ComposableRecorder::stopRecording, this, std::placeholders::_1, std::placeholders::_2));
}

bool ComposableRecorder::startRecording(
Expand All @@ -104,6 +104,16 @@ bool ComposableRecorder::startRecording(
res->message = "already recording!";
} else {
RCLCPP_INFO(get_logger(), "starting recording...");
#ifdef USE_GET_STORAGE_OPTIONS
rosbag2_storage::StorageOptions & sopt = get_storage_options();
#else
rosbag2_storage::StorageOptions & sopt = storage_options_;
#endif
if (!bag_name_.empty()) {
sopt.uri = bag_name_;
} else {
sopt.uri = bag_prefix_ + get_time_stamp();
}
try {
record();
isRecording_ = true;
Expand All @@ -118,6 +128,31 @@ bool ComposableRecorder::startRecording(
return (true);
}

bool ComposableRecorder::stopRecording(
const std::shared_ptr<std_srvs::srv::Trigger::Request> req,
std::shared_ptr<std_srvs::srv::Trigger::Response> res)
{
(void)req;
res->success = false;
if (!isRecording_) {
RCLCPP_WARN(get_logger(), "not recording yet!");
res->message = "not recording yet!";
} else {
RCLCPP_INFO(get_logger(), "stopping recording...");
try {
stop();
isRecording_ = false;
RCLCPP_INFO(get_logger(), "stopped recording successfully");
res->success = true;
res->message = "stopped recoding!";
} catch (const std::runtime_error & e) {
RCLCPP_WARN(get_logger(), "cannot toggle recording!");
res->message = "runtime error occurred: " + std::string(e.what());
}
}
return (true);
}

ComposableRecorder::~ComposableRecorder() {}
} // namespace rosbag2_composable_recorder

Expand Down

0 comments on commit b398a6b

Please sign in to comment.