Skip to content

Commit d19b762

Browse files
committed
Add optional uri parameter for the Recorder::record(uri) API
Note: if provided optional parameter uri, it will override the storage_options.uri provided during construction. Signed-off-by: Michael Orlov <[email protected]>
1 parent 735901d commit d19b762

File tree

2 files changed

+18
-10
lines changed

2 files changed

+18
-10
lines changed

rosbag2_transport/include/rosbag2_transport/recorder.hpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -117,12 +117,14 @@ class Recorder : public rclcpp::Node
117117
ROSBAG2_TRANSPORT_PUBLIC
118118
virtual ~Recorder();
119119

120+
/// \brief Start recording.
121+
/// \param uri If provided, it will override the storage_options.uri provided during construction.
120122
ROSBAG2_TRANSPORT_PUBLIC
121-
void record();
123+
void record(const std::string & uri = "");
122124

123125
/// @brief Stopping recording.
124-
/// @details The stop() is opposite to the record() operation. It will stop recording, dump
125-
/// all buffers to the disk and close writer. The record() can be called again after stop().
126+
/// @details The stop() is opposite to the record(uri) operation. It will stop recording, dump
127+
/// all buffers to the disk and close writer. The record(uri) can be called again after stop().
126128
ROSBAG2_TRANSPORT_PUBLIC
127129
void stop();
128130

rosbag2_transport/src/rosbag2_transport/recorder.cpp

Lines changed: 13 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -63,10 +63,12 @@ class RecorderImpl
6363

6464
~RecorderImpl();
6565

66-
void record();
66+
/// \brief Start recording.
67+
/// \param uri If provided, it will override the storage_options.uri provided during construction.
68+
void record(const std::string & uri = "");
6769

6870
/// @brief Stopping recording and closing writer.
69-
/// The record() can be called again after stop().
71+
/// The record(uri) can be called again after stop().
7072
void stop();
7173

7274
const rosbag2_cpp::Writer & get_writer_handle();
@@ -257,15 +259,19 @@ void RecorderImpl::stop()
257259
}
258260
}
259261

260-
void RecorderImpl::record()
262+
void RecorderImpl::record(const std::string & uri)
261263
{
262264
std::lock_guard<std::mutex> state_lock(start_stop_transition_mutex_);
263265
if (in_recording_.exchange(true)) {
264266
RCLCPP_WARN_STREAM(
265267
node->get_logger(),
266-
"Called Recorder::record() while already in recording, dismissing request.");
268+
"Called Recorder::record(uri) while already in recording, dismissing request.");
267269
return;
268270
}
271+
if (!uri.empty()) {
272+
storage_options_.uri = uri;
273+
}
274+
RCLCPP_INFO(node->get_logger(), "Starting recording to '%s'", storage_options_.uri.c_str());
269275
paused_ = record_options_.start_paused;
270276
topic_qos_profile_overrides_ = record_options_.topic_qos_profile_overrides;
271277
// Check serialization format options
@@ -447,7 +453,7 @@ void RecorderImpl::start_discovery()
447453
// Get graph event to ensure to start GrapListener if not already started and register event,
448454
// before we're starting discovery thread.
449455
// This is a workaround to split initialization and runtime phases to avoid race condition when
450-
// a new publisher appeared after we finish start_discovery() and/or Recorder::record(),
456+
// a new publisher appeared after we finish start_discovery() and/or Recorder::record(uri),
451457
// but before we really start topics_discovery() thread.
452458
discovery_graph_event_ = node->get_graph_event();
453459
discovery_future_ =
@@ -839,9 +845,9 @@ Recorder::Recorder(
839845

840846
Recorder::~Recorder() = default;
841847

842-
void Recorder::record()
848+
void Recorder::record(const std::string & uri)
843849
{
844-
pimpl_->record();
850+
pimpl_->record(uri);
845851
}
846852

847853
void Recorder::stop()

0 commit comments

Comments
 (0)