Skip to content

Commit 36978ea

Browse files
committed
Add options to conditionally stop the recording
- publish event when recording stops Signed-off-by: Nicola Loi <[email protected]>
1 parent ffd8c7d commit 36978ea

File tree

19 files changed

+511
-14
lines changed

19 files changed

+511
-14
lines changed

README.md

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,18 @@ Messages written to the bag will use the latest received value of `/clock` for t
7474
Note: Until the first `/clock` message is received, the recorder will not write any messages.
7575
Before that message is received, the time is 0, which leads to a significant time jump once simulation time begins, making the bag essentially unplayable if messages are written first with time 0 and then time N from `/clock`.
7676

77+
#### Recording with termination conditions
78+
79+
rosbag2 can be configured to stop recording after a certain size, duration or number of messages is reached (considering **all** the bag files of the current recording). By default the recording will continue until an external signal is stopping it, but this can be changed using the CLI options.
80+
81+
_Stopping by size_: `ros2 bag record -a --max-recording-size 100000` will stop the recording after it becomes greater than 100 kilobytes. This option defaults to `0`, which means the recording will not stop based on size.
82+
83+
_Stopping by duration_: `ros2 bag record -a --max-recording-duration 9000` will stop the recording after `9000` seconds. This option defaults to `0`, which means the recording will not stop based on duration.
84+
85+
_Stopping by number of messages_: `ros2 bag record -a --max-recording-messages 1000` will stop the recording after `1000` messages have been recorded. This option defaults to `0`, which means the recording will not stop based on number of messages.
86+
87+
If multiple stopping conditions are enabled, the recording will stop at whichever threshold is reached first.
88+
7789
#### Splitting files during recording
7890

7991
rosbag2 offers the capability to split bag files when they reach a maximum size or after a specified duration. By default rosbag2 will record all data into a single bag file, but this can be changed using the CLI options.
@@ -253,6 +265,9 @@ output_bags:
253265
storage_id: "" # will use the default storage plugin, if unspecified
254266
max_bagfile_size: 0
255267
max_bagfile_duration: 0
268+
max_recording_size: 0
269+
max_recording_duration: 0
270+
max_recording_messages: 0
256271
storage_preset_profile: ""
257272
storage_config_uri: ""
258273
all_topics: false

ros2bag/ros2bag/verb/record.py

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -145,6 +145,18 @@ def add_recorder_arguments(parser: ArgumentParser) -> None:
145145
'Default: %(default)d, recording written in single bagfile and splitting '
146146
'is disabled. If both splitting by size and duration are enabled, '
147147
'the bag will split at whichever threshold is reached first.')
148+
parser.add_argument(
149+
'--max-recording-size', type=int, default=0,
150+
help='Maximum size in bytes before the recording will be stopped. '
151+
'Default: %(default)d, recording will not stop based on size.')
152+
parser.add_argument(
153+
'--max-recording-duration', type=int, default=0,
154+
help='Maximum duration in seconds before the recording will be stopped. '
155+
'Default: %(default)d, recording will not stop based on duration.')
156+
parser.add_argument(
157+
'--max-recording-messages', type=int, default=0,
158+
help='Maximum number of messages before the recording will be stopped. '
159+
'Default: %(default)d, recording will not stop based on number of messages.')
148160
parser.add_argument(
149161
'--max-cache-size', type=int, default=100 * 1024 * 1024,
150162
help='Maximum size (in bytes) of messages to hold in each buffer of cache. '
@@ -325,7 +337,10 @@ def main(self, *, args): # noqa: D102
325337
storage_preset_profile=args.storage_preset_profile,
326338
storage_config_uri=storage_config_file,
327339
snapshot_mode=args.snapshot_mode,
328-
custom_data=custom_data
340+
custom_data=custom_data,
341+
max_recording_size=args.max_recording_size,
342+
max_recording_duration=args.max_recording_duration,
343+
max_recording_messages=args.max_recording_messages,
329344
)
330345
record_options = RecordOptions()
331346
record_options.all_topics = args.all_topics or args.all

rosbag2_cpp/include/rosbag2_cpp/bag_events.hpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ enum class BagEvent
3838
WRITE_SPLIT,
3939
/// Reading of the input bag file has gone over a split, opening the next file.
4040
READ_SPLIT,
41+
/// The recording has reached a predetermined stopping condition.
42+
STOP_RECORDING
4143
};
4244

4345
/**
@@ -51,7 +53,19 @@ struct BagSplitInfo
5153
std::string opened_file;
5254
};
5355

56+
/**
57+
* \brief The information structure passed to callbacks for the STOP_RECORDING event.
58+
*/
59+
struct StopRecordingInfo
60+
{
61+
/// The base folder where the recording was taking place.
62+
std::string base_folder;
63+
/// The reason for stopping the recording.
64+
std::string reason;
65+
};
66+
5467
using BagSplitCallbackType = std::function<void (BagSplitInfo &)>;
68+
using BagStopRecordingCallbackType = std::function<void (StopRecordingInfo &)>;
5569

5670
/**
5771
* \brief Use this structure to register callbacks with Writers.
@@ -60,6 +74,8 @@ struct WriterEventCallbacks
6074
{
6175
/// The callback to call for the WRITE_SPLIT event.
6276
BagSplitCallbackType write_split_callback;
77+
/// The callback to call for the STOP_RECORDING event.
78+
BagStopRecordingCallbackType stop_recording_callback;
6379
};
6480

6581
/**
Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
// Copyright 2025 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef ROSBAG2_CPP__STOP_RECORDING_OPTIONS_HPP_
16+
#define ROSBAG2_CPP__STOP_RECORDING_OPTIONS_HPP_
17+
18+
#include <cstdint>
19+
20+
namespace rosbag2_cpp
21+
{
22+
23+
struct StopRecordingOptions
24+
{
25+
uint64_t max_duration;
26+
uint64_t max_size;
27+
uint64_t max_messages;
28+
};
29+
30+
} // namespace rosbag2_cpp
31+
32+
#endif // ROSBAG2_CPP__STOP_RECORDING_OPTIONS_HPP_

rosbag2_cpp/include/rosbag2_cpp/writer.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727

2828
#include "rosbag2_cpp/bag_events.hpp"
2929
#include "rosbag2_cpp/converter_options.hpp"
30+
#include "rosbag2_cpp/stop_recording_options.hpp"
3031
#include "rosbag2_cpp/visibility_control.hpp"
3132
#include "rosbag2_cpp/writers/sequential_writer.hpp"
3233

rosbag2_cpp/include/rosbag2_cpp/writers/sequential_writer.hpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,10 @@ class ROSBAG2_CPP_PUBLIC SequentialWriter
158158
void execute_bag_split_callbacks(
159159
const std::string & closed_file, const std::string & opened_file);
160160

161+
void signal_stop_recording(const std::string & out_stop_reason);
162+
163+
void execute_signal_stop_recording_callbacks(const std::string & out_stop_reason);
164+
161165
void switch_to_next_storage();
162166

163167
std::string format_storage_uri(
@@ -183,6 +187,16 @@ class ROSBAG2_CPP_PUBLIC SequentialWriter
183187
bool should_split_bagfile(
184188
const std::chrono::time_point<std::chrono::high_resolution_clock> & current_time) const;
185189

190+
// Checks if the recording needs to be stopped due to predefined conditions
191+
// before writing the current message.
192+
bool should_stop_recording_pre_write(
193+
const std::chrono::time_point<std::chrono::high_resolution_clock> & current_time,
194+
std::string & stop_reason) const;
195+
196+
// Checks if the recording needs to be stopped due to predefined conditions
197+
// after writing the current message.
198+
bool should_stop_recording_post_write(std::string & stop_reason) const;
199+
186200
// Checks if the message to be written is within accepted time range
187201
bool message_within_accepted_time_range(
188202
const rcutils_time_point_value_t current_time) const;
@@ -200,6 +214,15 @@ class ROSBAG2_CPP_PUBLIC SequentialWriter
200214
get_writeable_message(
201215
std::shared_ptr<const rosbag2_storage::SerializedBagMessage> message);
202216

217+
// Used to track the approximate size of the previously splitted bags.
218+
uint64_t previous_bags_size_ {0};
219+
220+
// Used to track the number of messages in the previously splitted bags.
221+
uint64_t previous_bags_num_messages_ {0};
222+
223+
// Used to track if the stop recording signal has been already sent.
224+
bool signaled_stop_recording_ {false};
225+
203226
private:
204227
/// Helper method to write messages while also updating tracked metadata.
205228
void write_messages(

rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp

Lines changed: 87 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -327,6 +327,9 @@ void SequentialWriter::switch_to_next_storage()
327327
message_cache_->log_dropped();
328328
}
329329

330+
previous_bags_size_ += storage_->get_bagfile_size();
331+
previous_bags_num_messages_ += metadata_.files.back().message_count;
332+
330333
storage_->update_metadata(metadata_);
331334
storage_options_.uri = format_storage_uri(
332335
base_folder_,
@@ -385,8 +388,30 @@ void SequentialWriter::split_bagfile()
385388
(void)split_bagfile_local();
386389
}
387390

391+
void SequentialWriter::signal_stop_recording(const std::string & reason)
392+
{
393+
if (signaled_stop_recording_) {
394+
return;
395+
}
396+
execute_signal_stop_recording_callbacks(reason);
397+
signaled_stop_recording_ = true;
398+
}
399+
400+
void SequentialWriter::execute_signal_stop_recording_callbacks(
401+
const std::string & reason)
402+
{
403+
auto info = std::make_shared<bag_events::StopRecordingInfo>();
404+
info->base_folder = base_folder_;
405+
info->reason = reason;
406+
callback_manager_.execute_callbacks(bag_events::BagEvent::STOP_RECORDING, info);
407+
}
408+
388409
void SequentialWriter::write(std::shared_ptr<const rosbag2_storage::SerializedBagMessage> message)
389410
{
411+
if (signaled_stop_recording_) {
412+
return;
413+
}
414+
390415
if (!is_open_) {
391416
throw std::runtime_error("Bag is not open. Call open() before writing.");
392417
}
@@ -415,6 +440,12 @@ void SequentialWriter::write(std::shared_ptr<const rosbag2_storage::SerializedBa
415440
is_first_message_ = false;
416441
}
417442

443+
std::string out_stop_reason;
444+
if (should_stop_recording_pre_write(message_timestamp, out_stop_reason)) {
445+
signal_stop_recording(out_stop_reason);
446+
return;
447+
}
448+
418449
if (!storage_options_.snapshot_mode && should_split_bagfile(message_timestamp)) {
419450
split_bagfile();
420451
metadata_.files.back().starting_time = message_timestamp;
@@ -442,6 +473,11 @@ void SequentialWriter::write(std::shared_ptr<const rosbag2_storage::SerializedBa
442473
// Otherwise, use cache buffer
443474
message_cache_->push(converted_msg);
444475
}
476+
477+
if (should_stop_recording_post_write(out_stop_reason)) {
478+
signal_stop_recording(out_stop_reason);
479+
return;
480+
}
445481
}
446482

447483
bool SequentialWriter::take_snapshot()
@@ -508,6 +544,52 @@ bool SequentialWriter::message_within_accepted_time_range(
508544
return true;
509545
}
510546

547+
bool SequentialWriter::should_stop_recording_pre_write(
548+
const std::chrono::time_point<std::chrono::high_resolution_clock> & current_time,
549+
std::string & out_stop_reason) const
550+
{
551+
// Stopping by time
552+
if (storage_options_.max_recording_duration !=
553+
rosbag2_storage::storage_interfaces::MAX_RECORDING_DURATION_NO_STOP)
554+
{
555+
auto max_duration_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
556+
std::chrono::seconds(storage_options_.max_recording_duration));
557+
if ((current_time - metadata_.starting_time) > max_duration_ns) {
558+
out_stop_reason = "max duration";
559+
return true;
560+
}
561+
}
562+
563+
return false;
564+
}
565+
566+
bool SequentialWriter::should_stop_recording_post_write(std::string & out_stop_reason) const
567+
{
568+
// Stopping by size
569+
if (storage_options_.max_recording_size !=
570+
rosbag2_storage::storage_interfaces::MAX_RECORDING_SIZE_NO_STOP)
571+
{
572+
if (previous_bags_size_ + storage_->get_bagfile_size() >= storage_options_.max_recording_size) {
573+
out_stop_reason = "max size";
574+
return true;
575+
}
576+
}
577+
578+
// Stopping by number of messages
579+
if (storage_options_.max_recording_messages !=
580+
rosbag2_storage::storage_interfaces::MAX_RECORDING_MESSAGES_NO_STOP)
581+
{
582+
if (previous_bags_num_messages_ + metadata_.files.back().message_count >=
583+
storage_options_.max_recording_messages)
584+
{
585+
out_stop_reason = "max messages";
586+
return true;
587+
}
588+
}
589+
590+
return false;
591+
}
592+
511593
void SequentialWriter::finalize_metadata()
512594
{
513595
metadata_.bag_size = 0;
@@ -563,6 +645,11 @@ void SequentialWriter::add_event_callbacks(const bag_events::WriterEventCallback
563645
callbacks.write_split_callback,
564646
bag_events::BagEvent::WRITE_SPLIT);
565647
}
648+
if (callbacks.stop_recording_callback) {
649+
callback_manager_.add_event_callback(
650+
callbacks.stop_recording_callback,
651+
bag_events::BagEvent::STOP_RECORDING);
652+
}
566653
}
567654

568655
} // namespace writers

rosbag2_interfaces/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ find_package(rosidl_default_generators REQUIRED)
1515

1616
rosidl_generate_interfaces(${PROJECT_NAME}
1717
"msg/ReadSplitEvent.msg"
18+
"msg/StopRecordingEvent.msg"
1819
"msg/WriteSplitEvent.msg"
1920
"srv/Burst.srv"
2021
"srv/GetRate.srv"
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
# The full path of the base folder where the recording was taking place.
2+
string base_folder
3+
4+
# The reason for stopping the recording.
5+
string reason
6+
7+
# The fully qualified node name of the event sender
8+
string node_name

rosbag2_py/rosbag2_py/_storage.pyi

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,13 +101,16 @@ class StorageOptions:
101101
max_bagfile_duration: int
102102
max_bagfile_size: int
103103
max_cache_size: int
104+
max_recording_duration: int
105+
max_recording_messages: int
106+
max_recording_size: int
104107
snapshot_mode: bool
105108
start_time_ns: int
106109
storage_config_uri: str
107110
storage_id: str
108111
storage_preset_profile: str
109112
uri: str
110-
def __init__(self, uri: str, storage_id: str = ..., max_bagfile_size: int = ..., max_bagfile_duration: int = ..., max_cache_size: int = ..., storage_preset_profile: str = ..., storage_config_uri: str = ..., snapshot_mode: bool = ..., start_time_ns: int = ..., end_time_ns: int = ..., custom_data: Dict[str, str] = ...) -> None: ...
113+
def __init__(self, uri: str, storage_id: str = ..., max_bagfile_size: int = ..., max_bagfile_duration: int = ..., max_cache_size: int = ..., storage_preset_profile: str = ..., storage_config_uri: str = ..., snapshot_mode: bool = ..., start_time_ns: int = ..., end_time_ns: int = ..., custom_data: Dict[str, str] = ..., max_recording_size: int = ..., max_recording_duration: int = ..., max_recording_messages: int = ...) -> None: ...
111114

112115
class TopicInformation:
113116
message_count: int

0 commit comments

Comments
 (0)