Skip to content

Conversation

@MichaelOrlov
Copy link
Contributor

@MichaelOrlov MichaelOrlov commented Nov 26, 2025

Description

This PR is a replacement for the stale PR #1840 and adds the following services to the rosbag2_transport::Recorder

Is this user-facing behavior change?

Yes. The user will have the ability to manage the Rosbag2 recorder instance remotely via the service calls.

Did you use Generative AI?

Yes. I am using GitHub Copilot, GPT-5.0, mostly to help me with tests and Doxygen comments.

Additional Information

No APi/ABI breaking changes -> can be backported

@MichaelOrlov
Copy link
Contributor Author

@ros-pull-request-builder retest this please

@MichaelOrlov
Copy link
Contributor Author

@christophebedard @fujitatomoya Friendly ping here for review. Or maybe @ahcorde or @Barry-Xu-2018 some of you can review this PR?

Copy link
Contributor

@Barry-Xu-2018 Barry-Xu-2018 left a comment

Choose a reason for hiding this comment

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

LGTM.

I have a small question.

In RecorderImpl::stop(), in_recording_ is set to false only after the stop processing is completed.

void RecorderImpl::stop()
{
std::lock_guard<std::mutex> state_lock(start_stop_transition_mutex_);
if (!in_recording_) {
RCLCPP_DEBUG(node->get_logger(), "Recording has already been stopped or not running.");
return;
}
stop_discovery();
pause();
subscriptions_.clear();
writer_->close(); // Call writer->close() to finalize current bag file and write metadata
in_recording_ = false;

In RecorderImpl::record(), in_recording_ is set to true before record processing is complete.

void RecorderImpl::record(const std::string & uri)
{
std::lock_guard<std::mutex> state_lock(start_stop_transition_mutex_);
if (in_recording_.exchange(true)) {

In RecorderImpl::stop(), is it possible to set in_recording_ to false before stop processing is started ? (I'm not sure if there were any specific considerations for current implementation.)

Considering that there is some processing time between when RecorderImpl::stop() is called and when in_recording_ is set to false, if a service callback is invoked during this period, the first check of in_recording_ would be meaningless.

  srv_stop_ = node->create_service<rosbag2_interfaces::srv::Stop>(
    "~/stop",
    [this](
      const std::shared_ptr<rmw_request_id_t>/* request_header */,
      const std::shared_ptr<rosbag2_interfaces::srv::Stop::Request>/* request */,
      const std::shared_ptr<rosbag2_interfaces::srv::Stop::Response>/* response */)
    {
      if (!in_recording_) {
        RCLCPP_WARN(node->get_logger(),
          "Received Stop request while not in recording. Ignoring request.");
      } else {
        try {
          this->stop();
        } catch (const std::exception & e) {
          RCLCPP_ERROR(node->get_logger(), "Error during Stop request: %s", e.what());
        }
      }
    }
  );

@MichaelOrlov
Copy link
Contributor Author

@Barry-Xu-2018, good question and catch-up.
We use if (in_recording_.exchange(true)) in the record(uri) method as a leftover from the times when we were using it without a mutex lock.

void RecorderImpl::record(const std::string & uri)
{
std::lock_guard<std::mutex> state_lock(start_stop_transition_mutex_);
if (in_recording_.exchange(true)) {

You are right, we shall set in_recording_ = true; at the end of the record(uri) method when the recorder and all its underlying data types are fully initialized and ready for recording to avoid race conditions and undefined behavior.

I made a fix in my last 0b2e478 commit

@MichaelOrlov
Copy link
Contributor Author

@christophebedard @fujitatomoya @ahcorde This PR was reviewed, and findings were addressed. Can some of you formally approve this PR or review it additionally?

@MichaelOrlov
Copy link
Contributor Author

Pulls: #2248
Gist: https://gist.githubusercontent.com/MichaelOrlov/a037975e5fc0e47f16e9b4531842f99f/raw/4f6447b9d365c81b919c094079a426d215d6c412/ros2.repos
BUILD args: --packages-above-and-dependencies rosbag2_transport rosbag2_tests
TEST args: --packages-above rosbag2_transport rosbag2_tests
ROS Distro: rolling
Job: ci_launcher
ci_launcher ran: https://ci.ros2.org/job/ci_launcher/17856

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Linux-rhel Build Status
  • Windows Build Status

- Rationale:
  We use in_recording_ check in service calls, therefore the recorder
  and all its underlying data types shall be fully initialized and ready
  before we set this flag to true.

Signed-off-by: Michael Orlov <[email protected]>
@MichaelOrlov MichaelOrlov force-pushed the morlov/add-record-stop-discovery-services branch from 2978286 to 06e26d2 Compare January 7, 2026 18:08
@MichaelOrlov
Copy link
Contributor Author

Made a rebase and resolved conflicts.

@MichaelOrlov
Copy link
Contributor Author

@ahcorde @fujitatomoya A friendly ping for a formal approval or additional review here.

@MichaelOrlov
Copy link
Contributor Author

Re-run CI after rebase and fixing conflicts
ci_launcher ran: https://ci.ros2.org/job/ci_launcher/17878

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Linux-rhel Build Status
  • Windows Build Status

Copy link
Contributor

@fujitatomoya fujitatomoya left a comment

Choose a reason for hiding this comment

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

just a few minor comments. overall lgtm with all comments are resolved.

Comment on lines +1 to +4
---
# True if discovery is running, false otherwise
bool running

Copy link
Contributor

Choose a reason for hiding this comment

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

(this comment does not block the PR)

although i understand there is already ~/is_paused as a service (this is consistent for the current implementation), i would use a read only parameter instead here. this is purely a state query with no side effects, and i believe exactly what parameters are designed for. in this way, we can reduce service endpoint to take advantage of internal parameter service.

const std::shared_ptr<rosbag2_interfaces::srv::Record::Request> request,
const std::shared_ptr<rosbag2_interfaces::srv::Record::Response> response)
{
if (in_recording_) {
Copy link
Contributor

Choose a reason for hiding this comment

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

are we missing mutex here?

Suggested change
if (in_recording_) {
std::lock_guard<std::mutex> state_lock(start_stop_transition_mutex_);
if (in_recording_) {

const std::shared_ptr<rosbag2_interfaces::srv::Stop::Request>/* request */,
const std::shared_ptr<rosbag2_interfaces::srv::Stop::Response>/* response */)
{
if (!in_recording_) {
Copy link
Contributor

Choose a reason for hiding this comment

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

same here?

Suggested change
if (!in_recording_) {
std::lock_guard<std::mutex> state_lock(start_stop_transition_mutex_);
if (!in_recording_) {

try {
this->stop();
} catch (const std::exception & e) {
RCLCPP_ERROR(node->get_logger(), "Error during Stop request: %s", e.what());
Copy link
Contributor

Choose a reason for hiding this comment

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

probably we can consider adding return_code/error_string to the Stop response for consistency with other services? errors are only logged, not returned to the caller.

#include <algorithm>
#include <chrono>
#include <cstdint>
#include <condition_variable>
Copy link
Contributor

Choose a reason for hiding this comment

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

is this required to add? doesn't appear to be used.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Add record, stop, start_discovery and stop_discovery services for rosbag2_transport::Recorder

5 participants