Skip to content

Commit

Permalink
Add snapshot_duration handling in composable recorder and player nodes
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 2eb2450 commit eba69a7
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -375,6 +375,9 @@ get_storage_options_from_node_params(rclcpp::Node & node)

storage_options.snapshot_mode = node.declare_parameter<bool>("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<std::vector<std::string>>(
"storage.custom_data",
std::vector<std::string>());
Expand Down
1 change: 1 addition & 0 deletions rosbag2_transport/test/resources/recorder_node_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ recorder_params_node:
max_cache_size: 989888
storage_preset_profile: "none"
snapshot_mode: false
snapshot_duration: 1.5
custom_data: ["key1=value1", "key2=value2"]
start_time_ns: 0
end_time_ns: 100000
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, std::string> custom_data{
std::pair{"key1", "value1"},
std::pair{"key2", "value2"}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, std::string> custom_data{
std::pair{"key1", "value1"},
std::pair{"key2", "value2"}
Expand Down

0 comments on commit eba69a7

Please sign in to comment.