diff --git a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp index ef6408db7..73df125b6 100644 --- a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp +++ b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp @@ -375,6 +375,9 @@ get_storage_options_from_node_params(rclcpp::Node & node) storage_options.snapshot_mode = node.declare_parameter("storage.snapshot_mode", false); + storage_options.snapshot_duration = + param_utils::get_duration_from_node_param(node, "storage.snapshot_duration", 0, 0); + auto list_of_key_value_strings = node.declare_parameter>( "storage.custom_data", std::vector()); diff --git a/rosbag2_transport/test/resources/player_node_params.yaml b/rosbag2_transport/test/resources/player_node_params.yaml index 79e1b47a9..48cb71d8e 100644 --- a/rosbag2_transport/test/resources/player_node_params.yaml +++ b/rosbag2_transport/test/resources/player_node_params.yaml @@ -49,4 +49,7 @@ player_params_node: max_cache_size: 9898 storage_preset_profile: "resilient" snapshot_mode: false + snapshot_duration: + sec: 1 + nsec: 500000000 custom_data: ["key1=value1", "key2=value2"] \ No newline at end of file diff --git a/rosbag2_transport/test/resources/recorder_node_params.yaml b/rosbag2_transport/test/resources/recorder_node_params.yaml index 701f623bf..c295e803d 100644 --- a/rosbag2_transport/test/resources/recorder_node_params.yaml +++ b/rosbag2_transport/test/resources/recorder_node_params.yaml @@ -41,6 +41,9 @@ recorder_params_node: max_cache_size: 989888 storage_preset_profile: "none" snapshot_mode: false + snapshot_duration: + sec: 1 + nsec: 500000000 custom_data: ["key1=value1", "key2=value2"] start_time_ns: 0 end_time_ns: 100000 diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp index 3875a0b1b..99b31de2b 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp @@ -186,6 +186,7 @@ TEST_P(ComposablePlayerTests, player_can_parse_parameters_from_file) { EXPECT_EQ(storage_options.max_cache_size, 9898); EXPECT_EQ(storage_options.storage_preset_profile, "resilient"); EXPECT_EQ(storage_options.snapshot_mode, false); + EXPECT_DOUBLE_EQ(storage_options.snapshot_duration.seconds(), 1.5); std::unordered_map custom_data{ std::pair{"key1", "value1"}, std::pair{"key2", "value2"} diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp index 97a89bc5a..f6d18bbe3 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp @@ -256,6 +256,7 @@ TEST_P(ComposableRecorderTests, recorder_can_parse_parameters_from_file) { EXPECT_EQ(storage_options.max_cache_size, 989888); EXPECT_EQ(storage_options.storage_preset_profile, "none"); EXPECT_EQ(storage_options.snapshot_mode, false); + EXPECT_DOUBLE_EQ(storage_options.snapshot_duration.seconds(), 1.5); std::unordered_map custom_data{ std::pair{"key1", "value1"}, std::pair{"key2", "value2"}