Skip to content

Commit 62b081c

Browse files
committed
Add circular logging by split count
- Add StorageOptions.max_splits (+ YAML/params, Python bindings) - CLI: --max-splits (before size/duration) - Writer: delete oldest files when exceeding size, duration, or split count
1 parent 958aa12 commit 62b081c

File tree

10 files changed

+40
-9
lines changed

10 files changed

+40
-9
lines changed

ros2bag/ros2bag/verb/record.py

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -159,6 +159,11 @@ def add_recorder_arguments(parser: ArgumentParser) -> None:
159159
'Default: %(default)d, recording written in single bagfile and splitting '
160160
'is disabled. If both splitting by size and duration are enabled, '
161161
'the bag will split at whichever threshold is reached first.')
162+
parser.add_argument(
163+
'--max-splits', type=int, default=0,
164+
help='Maximum number of splits to retain before deleting the oldest bagfile '
165+
'(circular logging). Default: %(default)d, unlimited. '
166+
'Requires --max-bag-size or --max-bag-duration to be set.')
162167
parser.add_argument(
163168
'--max-record-size', type=int, default=0,
164169
help='Maximum total size in bytes for the entire recording across all splits. '
@@ -376,6 +381,7 @@ def main(self, *, args): # noqa: D102
376381
max_bagfile_size=args.max_bag_size,
377382
max_bagfile_duration=args.max_bag_duration,
378383
max_cache_size=args.max_cache_size,
384+
max_splits=args.max_splits,
379385
max_record_size=args.max_record_size,
380386
max_record_duration=args.max_record_duration,
381387
storage_preset_profile=args.storage_preset_profile,

rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,7 @@ void Reindexer::aggregate_metadata(
182182
storage_options.storage_id,
183183
storage_options.max_bagfile_size,
184184
storage_options.max_bagfile_duration,
185+
storage_options.max_splits,
185186
storage_options.max_record_size,
186187
storage_options.max_record_duration,
187188
storage_options.max_cache_size,

rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp

Lines changed: 11 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -552,16 +552,18 @@ uint64_t SequentialWriter::get_total_record_duration() const
552552

553553
void SequentialWriter::delete_oldest_files_if_needed()
554554
{
555-
// Only delete if max_record_size or max_record_duration is set (circular buffer mode)
555+
// Only delete if any circular buffer limit is set (size, duration, or split count)
556556
// Note: This is only called after split_bagfile(), so max_bagfile_size is guaranteed to be set
557-
if (storage_options_.max_record_size == 0 && storage_options_.max_record_duration == 0) {
557+
if (storage_options_.max_record_size == 0 &&
558+
storage_options_.max_record_duration == 0 &&
559+
storage_options_.max_splits == 0) {
558560
return;
559561
}
560562

561563
// Protect metadata access with mutex to prevent race conditions
562564
std::lock_guard<std::mutex> lock(topics_info_mutex_);
563565

564-
// Delete oldest files until we're under both limits (if set)
566+
// Delete oldest files until we're under all configured limits (if set)
565567
// Note: We just split, so we have at least 2 files and the oldest is definitely not current
566568
while (metadata_.files.size() > 1) {
567569
// Check if we need to delete based on size limit
@@ -572,8 +574,12 @@ void SequentialWriter::delete_oldest_files_if_needed()
572574
bool exceeds_duration_limit = (max_record_duration_ns_ != 0 &&
573575
get_total_record_duration() > max_record_duration_ns_);
574576

575-
// If we're under both limits (or they're not set), stop deleting
576-
if (!exceeds_size_limit && !exceeds_duration_limit) {
577+
// Check if we need to delete based on split-count limit
578+
bool exceeds_split_limit = (storage_options_.max_splits != 0 &&
579+
metadata_.files.size() > storage_options_.max_splits);
580+
581+
// If we're under all limits (or they're not set), stop deleting
582+
if (!exceeds_size_limit && !exceeds_duration_limit && !exceeds_split_limit) {
577583
break;
578584
}
579585

rosbag2_py/rosbag2_py/_storage.pyi

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -103,13 +103,16 @@ class StorageOptions:
103103
max_bagfile_duration: int
104104
max_bagfile_size: int
105105
max_cache_size: int
106+
max_splits: int
107+
max_record_size: int
108+
max_record_duration: int
106109
snapshot_mode: bool
107110
start_time_ns: int
108111
storage_config_uri: str
109112
storage_id: str
110113
storage_preset_profile: str
111114
uri: str
112-
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: ...
115+
def __init__(self, uri: str, storage_id: str = ..., max_bagfile_size: int = ..., max_bagfile_duration: int = ..., max_splits: int = ..., max_record_size: int = ..., max_record_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: ...
113116

114117
class TopicInformation:
115118
message_count: int

rosbag2_py/src/rosbag2_py/_storage.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,12 +82,13 @@ PYBIND11_MODULE(_storage, m) {
8282
pybind11::class_<rosbag2_storage::StorageOptions>(m, "StorageOptions")
8383
.def(
8484
pybind11::init<
85-
std::string, std::string, uint64_t, uint64_t, uint64_t, uint64_t, uint64_t, std::string, std::string, bool,
85+
std::string, std::string, uint64_t, uint64_t, uint64_t, uint64_t, uint64_t, uint64_t, std::string, std::string, bool,
8686
int64_t, int64_t, KEY_VALUE_MAP>(),
8787
pybind11::arg("uri"),
8888
pybind11::arg("storage_id") = "",
8989
pybind11::arg("max_bagfile_size") = 0,
9090
pybind11::arg("max_bagfile_duration") = 0,
91+
pybind11::arg("max_splits") = 0,
9192
pybind11::arg("max_record_size") = 0,
9293
pybind11::arg("max_record_duration") = 0,
9394
pybind11::arg("max_cache_size") = 0,
@@ -105,6 +106,9 @@ PYBIND11_MODULE(_storage, m) {
105106
.def_readwrite(
106107
"max_bagfile_duration",
107108
&rosbag2_storage::StorageOptions::max_bagfile_duration)
109+
.def_readwrite(
110+
"max_splits",
111+
&rosbag2_storage::StorageOptions::max_splits)
108112
.def_readwrite(
109113
"max_record_size",
110114
&rosbag2_storage::StorageOptions::max_record_size)

rosbag2_storage/include/rosbag2_storage/storage_options.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,11 @@ struct StorageOptions
3939
// A value of 0 indicates that bagfile splitting will not be used.
4040
uint64_t max_bagfile_duration = 0;
4141

42+
// The maximum number of bagfile splits to retain before the oldest bagfile is deleted.
43+
// A value of 0 indicates that no deletion based on split count will occur.
44+
// This feature is only available if either max_bagfile_size or max_bagfile_duration is set.
45+
uint64_t max_splits = 0;
46+
4247
// The maximum size a record can be, in bytes, before the oldest bagfile is deleted.
4348
// A value of 0 indicates that oldest bagfile is not deleted.
4449
// This feature is only available if either max_bagfile_size or max_bagfile_duration is set.

rosbag2_storage/src/rosbag2_storage/storage_options.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ Node convert<rosbag2_storage::StorageOptions>::encode(
2828
node["storage_id"] = storage_options.storage_id;
2929
node["max_bagfile_size"] = storage_options.max_bagfile_size;
3030
node["max_bagfile_duration"] = storage_options.max_bagfile_duration;
31+
node["max_splits"] = storage_options.max_splits;
3132
node["max_record_size"] = storage_options.max_record_size;
3233
node["max_record_duration"] = storage_options.max_record_duration;
3334
node["max_cache_size"] = storage_options.max_cache_size;
@@ -47,6 +48,7 @@ bool convert<rosbag2_storage::StorageOptions>::decode(
4748
optional_assign<std::string>(node, "storage_id", storage_options.storage_id);
4849
optional_assign<uint64_t>(node, "max_bagfile_size", storage_options.max_bagfile_size);
4950
optional_assign<uint64_t>(node, "max_bagfile_duration", storage_options.max_bagfile_duration);
51+
optional_assign<uint64_t>(node, "max_splits", storage_options.max_splits);
5052
optional_assign<uint64_t>(node, "max_record_size", storage_options.max_record_size);
5153
optional_assign<uint64_t>(node, "max_record_duration", storage_options.max_record_duration);
5254
optional_assign<uint64_t>(node, "max_cache_size", storage_options.max_cache_size);

rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -284,7 +284,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture
284284
out << config_yaml;
285285
}
286286

287-
rosbag2_storage::StorageOptions storage_options{storage_uri, plugin_id, 0, 0, 0, 0, 0,
287+
rosbag2_storage::StorageOptions storage_options{storage_uri, plugin_id, 0, 0, 0, 0, 0, 0,
288288
"", yaml_config};
289289
return storage_options;
290290
}

rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -524,7 +524,7 @@ TEST_F(StorageTestFixture, storage_preset_profile_applies_over_defaults) {
524524

525525
auto temp_dir = std::filesystem::path(temporary_dir_path_);
526526
const auto storage_uri = (temp_dir / "rosbag").generic_string();
527-
rosbag2_storage::StorageOptions options{storage_uri, kPluginID, 0, 0, 0, 0, 0, "", ""};
527+
rosbag2_storage::StorageOptions options{storage_uri, kPluginID, 0, 0, 0, 0, 0, 0, "", ""};
528528

529529
options.storage_preset_profile = "resilient";
530530
writable_storage->open(options, rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE);

rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -416,6 +416,10 @@ get_storage_options_from_node_params(rclcpp::Node & node)
416416
node, "storage.max_bagfile_duration", 0,
417417
std::numeric_limits<int64_t>::max(), storage_options.max_bagfile_duration);
418418

419+
storage_options.max_splits = param_utils::declare_integer_node_params<uint64_t>(
420+
node, "storage.max_splits", 0,
421+
std::numeric_limits<int64_t>::max(), storage_options.max_splits);
422+
419423
storage_options.max_record_size = param_utils::declare_integer_node_params<uint64_t>(
420424
node, "storage.max_record_size", 0,
421425
std::numeric_limits<int64_t>::max(), storage_options.max_record_size);

0 commit comments

Comments
 (0)