Skip to content

Commit 320edba

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 81ef9fd commit 320edba

File tree

2 files changed

+22
-14
lines changed

2 files changed

+22
-14
lines changed

rosbag2_transport/include/rosbag2_transport/recorder.hpp

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

120-
/// @brief Start recording.
121-
/// The record() method will return almost immediately and recording will happen in background.
120+
/// \brief Start recording.
121+
/// \details The record() method will return almost immediately and recording will happen in
122+
/// background.
123+
/// \param uri If provided, it will override the storage_options.uri provided during construction.
122124
ROSBAG2_TRANSPORT_PUBLIC
123-
void record();
125+
void record(const std::string & uri = "");
124126

125127
/// @brief Add a new channel (topic) to the rosbag2 writer to be recorded.
126128
/// \details This is a direct Recorder API equivalent to the rosbag2_cpp::Writer::add_topic().
@@ -214,8 +216,8 @@ class Recorder : public rclcpp::Node
214216
uint64_t get_total_num_messages_lost_in_transport() const;
215217

216218
/// @brief Stopping recording.
217-
/// @details The stop() is opposite to the record() operation. It will stop recording, dump
218-
/// all buffers to the disk and close writer. The record() can be called again after stop().
219+
/// @details The stop() is opposite to the record(uri) operation. It will stop recording, dump
220+
/// all buffers to the disk and close writer. The record(uri) can be called again after stop().
219221
ROSBAG2_TRANSPORT_PUBLIC
220222
void stop();
221223

rosbag2_transport/src/rosbag2_transport/recorder.cpp

Lines changed: 15 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -63,9 +63,11 @@ class RecorderImpl
6363

6464
~RecorderImpl();
6565

66-
/// @brief Start recording.
67-
/// The record() method will return almost immediately and recording will happen in background.
68-
void record();
66+
/// \brief Start recording.
67+
/// \details The record(uri) method will return almost immediately and recording will happen in
68+
/// background.
69+
/// \param uri If provided, it will override the storage_options.uri provided during construction.
70+
void record(const std::string & uri = "");
6971

7072
/// @brief Add a new channel (topic) to the rosbag2 writer to be recorded.
7173
/// \details This is a direct Recorder API equivalent to the rosbag2_cpp::Writer::add_topic().
@@ -156,7 +158,7 @@ class RecorderImpl
156158
uint64_t get_total_num_messages_lost_in_transport() const;
157159

158160
/// @brief Stopping recording and closing writer.
159-
/// The record() can be called again after stop().
161+
/// The record(uri) can be called again after stop().
160162
void stop();
161163

162164
/// Get a const reference to the underlying rosbag2 writer.
@@ -348,15 +350,19 @@ void RecorderImpl::stop()
348350
}
349351
}
350352

351-
void RecorderImpl::record()
353+
void RecorderImpl::record(const std::string & uri)
352354
{
353355
std::lock_guard<std::mutex> state_lock(start_stop_transition_mutex_);
354356
if (in_recording_.exchange(true)) {
355357
RCLCPP_WARN_STREAM(
356358
node->get_logger(),
357-
"Called Recorder::record() while already in recording, dismissing request.");
359+
"Called Recorder::record(uri) while already in recording, dismissing request.");
358360
return;
359361
}
362+
if (!uri.empty()) {
363+
storage_options_.uri = uri;
364+
}
365+
RCLCPP_INFO(node->get_logger(), "Starting recording to '%s'", storage_options_.uri.c_str());
360366
paused_ = record_options_.start_paused;
361367
topic_qos_profile_overrides_ = record_options_.topic_qos_profile_overrides;
362368
// Check serialization format options
@@ -538,7 +544,7 @@ void RecorderImpl::start_discovery()
538544
// Get graph event to ensure to start GrapListener if not already started and register event,
539545
// before we're starting discovery thread.
540546
// This is a workaround to split initialization and runtime phases to avoid race condition when
541-
// a new publisher appeared after we finish start_discovery() and/or Recorder::record(),
547+
// a new publisher appeared after we finish start_discovery() and/or Recorder::record(uri),
542548
// but before we really start topics_discovery() thread.
543549
discovery_graph_event_ = node->get_graph_event();
544550
discovery_future_ =
@@ -1018,9 +1024,9 @@ Recorder::Recorder(
10181024

10191025
Recorder::~Recorder() = default;
10201026

1021-
void Recorder::record()
1027+
void Recorder::record(const std::string & uri)
10221028
{
1023-
pimpl_->record();
1029+
pimpl_->record(uri);
10241030
}
10251031

10261032
void Recorder::add_channel(

0 commit comments

Comments
 (0)