Skip to content

Commit 0e076ec

Browse files
committed
Add snapshot_duration handling in composable recorder and player nodes
Signed-off-by: Michael Orlov <[email protected]>
1 parent 7986ede commit 0e076ec

File tree

5 files changed

+11
-0
lines changed

5 files changed

+11
-0
lines changed

rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -375,6 +375,9 @@ get_storage_options_from_node_params(rclcpp::Node & node)
375375

376376
storage_options.snapshot_mode = node.declare_parameter<bool>("storage.snapshot_mode", false);
377377

378+
storage_options.snapshot_duration =
379+
param_utils::get_duration_from_node_param(node, "storage.snapshot_duration", 0, 0);
380+
378381
auto list_of_key_value_strings = node.declare_parameter<std::vector<std::string>>(
379382
"storage.custom_data",
380383
std::vector<std::string>());

rosbag2_transport/test/resources/player_node_params.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -49,4 +49,7 @@ player_params_node:
4949
max_cache_size: 9898
5050
storage_preset_profile: "resilient"
5151
snapshot_mode: false
52+
snapshot_duration:
53+
sec: 1
54+
nsec: 500000000
5255
custom_data: ["key1=value1", "key2=value2"]

rosbag2_transport/test/resources/recorder_node_params.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,9 @@ recorder_params_node:
4141
max_cache_size: 989888
4242
storage_preset_profile: "none"
4343
snapshot_mode: false
44+
snapshot_duration:
45+
sec: 1
46+
nsec: 500000000
4447
custom_data: ["key1=value1", "key2=value2"]
4548
start_time_ns: 0
4649
end_time_ns: 100000

rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,7 @@ TEST_P(ComposablePlayerTests, player_can_parse_parameters_from_file) {
186186
EXPECT_EQ(storage_options.max_cache_size, 9898);
187187
EXPECT_EQ(storage_options.storage_preset_profile, "resilient");
188188
EXPECT_EQ(storage_options.snapshot_mode, false);
189+
EXPECT_DOUBLE_EQ(storage_options.snapshot_duration.seconds(), 1.5);
189190
std::unordered_map<std::string, std::string> custom_data{
190191
std::pair{"key1", "value1"},
191192
std::pair{"key2", "value2"}

rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -256,6 +256,7 @@ TEST_P(ComposableRecorderTests, recorder_can_parse_parameters_from_file) {
256256
EXPECT_EQ(storage_options.max_cache_size, 989888);
257257
EXPECT_EQ(storage_options.storage_preset_profile, "none");
258258
EXPECT_EQ(storage_options.snapshot_mode, false);
259+
EXPECT_DOUBLE_EQ(storage_options.snapshot_duration.seconds(), 1.5);
259260
std::unordered_map<std::string, std::string> custom_data{
260261
std::pair{"key1", "value1"},
261262
std::pair{"key2", "value2"}

0 commit comments

Comments
 (0)