Skip to content

Commit

Permalink
Rename snapshot_duration_ms to the snapshot_duration
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov committed Oct 28, 2024
1 parent 3d637f0 commit a126442
Show file tree
Hide file tree
Showing 7 changed files with 13 additions and 13 deletions.
2 changes: 1 addition & 1 deletion ros2bag/ros2bag/verb/record.py
Original file line number Diff line number Diff line change
Expand Up @@ -338,7 +338,7 @@ def main(self, *, args): # noqa: D102
storage_preset_profile=args.storage_preset_profile,
storage_config_uri=storage_config_file,
snapshot_mode=args.snapshot_mode,
snapshot_duration_ms=args.snapshot_duration,
snapshot_duration=args.snapshot_duration,
custom_data=custom_data
)
record_options = RecordOptions()
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ void SequentialWriter::open(
}

use_cache_ = storage_options.max_cache_size > 0u ||
(storage_options.snapshot_mode && storage_options.snapshot_duration_ms > 0);
(storage_options.snapshot_mode && storage_options.snapshot_duration > 0);
if (storage_options.snapshot_mode && !use_cache_) {
throw std::runtime_error(
"Either the max cache size or the maximum snapshot duration must be greater than 0"
Expand All @@ -155,7 +155,7 @@ void SequentialWriter::open(

if (use_cache_) {
if (storage_options.snapshot_mode) {
int64_t max_buffer_duration_ns = storage_options.snapshot_duration_ms * 1000000;
int64_t max_buffer_duration_ns = storage_options.snapshot_duration * 1000000;
message_cache_ = std::make_shared<rosbag2_cpp::cache::CircularMessageCache>(
storage_options.max_cache_size, max_buffer_duration_ns);
} else {
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_py/rosbag2_py/_storage.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -101,14 +101,14 @@ class StorageOptions:
max_bagfile_duration: int
max_bagfile_size: int
max_cache_size: int
snapshot_duration_ms: int
snapshot_duration: int
snapshot_mode: bool
start_time_ns: int
storage_config_uri: str
storage_id: str
storage_preset_profile: str
uri: str
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 = ..., snapshot_duration_ms: int = ..., start_time_ns: int = ..., end_time_ns: int = ..., custom_data: Dict[str, str] = ...) -> None: ...
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 = ..., snapshot_duration: int = ..., start_time_ns: int = ..., end_time_ns: int = ..., custom_data: Dict[str, str] = ...) -> None: ...

class TopicInformation:
message_count: int
Expand Down
6 changes: 3 additions & 3 deletions rosbag2_py/src/rosbag2_py/_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ PYBIND11_MODULE(_storage, m) {
pybind11::arg("storage_preset_profile") = "",
pybind11::arg("storage_config_uri") = "",
pybind11::arg("snapshot_mode") = false,
pybind11::arg("snapshot_duration_ms") = 0,
pybind11::arg("snapshot_duration") = 0,
pybind11::arg("start_time_ns") = -1,
pybind11::arg("end_time_ns") = -1,
pybind11::arg("custom_data") = KEY_VALUE_MAP{})
Expand All @@ -117,8 +117,8 @@ PYBIND11_MODULE(_storage, m) {
"snapshot_mode",
&rosbag2_storage::StorageOptions::snapshot_mode)
.def_readwrite(
"snapshot_duration_ms",
&rosbag2_storage::StorageOptions::snapshot_duration_ms)
"snapshot_duration",
&rosbag2_storage::StorageOptions::snapshot_duration)
.def_readwrite(
"start_time_ns",
&rosbag2_storage::StorageOptions::start_time_ns)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ struct StorageOptions

// The maximum snapshot duration in milliseconds.
// A value of 0 indicates that snapshot will be limited by the max_cache_size only.
int64_t snapshot_duration_ms = 0;
int64_t snapshot_duration = 0;

// Start and end time for cutting
int64_t start_time_ns = -1;
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_storage/src/rosbag2_storage/storage_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ Node convert<rosbag2_storage::StorageOptions>::encode(
node["storage_preset_profile"] = storage_options.storage_preset_profile;
node["storage_config_uri"] = storage_options.storage_config_uri;
node["snapshot_mode"] = storage_options.snapshot_mode;
node["snapshot_duration_ms"] = storage_options.snapshot_duration_ms;
node["snapshot_duration"] = storage_options.snapshot_duration;
node["start_time_ns"] = storage_options.start_time_ns;
node["end_time_ns"] = storage_options.end_time_ns;
node["custom_data"] = storage_options.custom_data;
Expand All @@ -51,7 +51,7 @@ bool convert<rosbag2_storage::StorageOptions>::decode(
node, "storage_preset_profile", storage_options.storage_preset_profile);
optional_assign<std::string>(node, "storage_config_uri", storage_options.storage_config_uri);
optional_assign<bool>(node, "snapshot_mode", storage_options.snapshot_mode);
optional_assign<int64_t>(node, "snapshot_duration_ms", storage_options.snapshot_duration_ms);
optional_assign<int64_t>(node, "snapshot_duration", storage_options.snapshot_duration);
optional_assign<int64_t>(node, "start_time_ns", storage_options.start_time_ns);
optional_assign<int64_t>(node, "end_time_ns", storage_options.end_time_ns);
using KEY_VALUE_MAP = std::unordered_map<std::string, std::string>;
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_storage/test/rosbag2_storage/test_storage_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ TEST(storage_options, test_yaml_serialization)
original.storage_preset_profile = "profile";
original.storage_config_uri = "config_uri";
original.snapshot_mode = true;
original.snapshot_duration_ms = 1500;
original.snapshot_duration = 1500;
original.start_time_ns = 12345000;
original.end_time_ns = 23456000;
original.custom_data["key1"] = "value1";
Expand All @@ -51,7 +51,7 @@ TEST(storage_options, test_yaml_serialization)
ASSERT_EQ(original.storage_preset_profile, reconstructed.storage_preset_profile);
ASSERT_EQ(original.storage_config_uri, reconstructed.storage_config_uri);
ASSERT_EQ(original.snapshot_mode, reconstructed.snapshot_mode);
ASSERT_EQ(original.snapshot_duration_ms, reconstructed.snapshot_duration_ms);
ASSERT_EQ(original.snapshot_duration, reconstructed.snapshot_duration);
ASSERT_EQ(original.start_time_ns, reconstructed.start_time_ns);
ASSERT_EQ(original.end_time_ns, reconstructed.end_time_ns);
ASSERT_EQ(original.custom_data, reconstructed.custom_data);
Expand Down

0 comments on commit a126442

Please sign in to comment.