From 5062b6e7caaa04eeeaf2e9546df737a814d5533b Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Thu, 13 Jun 2024 10:29:40 -0700 Subject: [PATCH] Bugfix for issue where unable to create composable nodes with compression (#1679) * Bugfix for unable to create composable nodes with compression - Use factory methods for creating reader and writer in constructors for composable Player and Recorder nodes. Signed-off-by: Michael Orlov * Address tests failures Signed-off-by: Michael Orlov --------- Signed-off-by: Michael Orlov --- rosbag2_transport/src/rosbag2_transport/player.cpp | 3 ++- rosbag2_transport/src/rosbag2_transport/recorder.cpp | 3 ++- rosbag2_transport/test/resources/recorder_node_params.yaml | 4 ++-- .../test/rosbag2_transport/test_composable_recorder.cpp | 4 ++-- 4 files changed, 8 insertions(+), 6 deletions(-) diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index 73df95b23..74a911f1d 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -40,6 +40,7 @@ #include "rosbag2_storage/qos.hpp" #include "rosbag2_transport/config_options_from_node_params.hpp" #include "rosbag2_transport/player_service_client.hpp" +#include "rosbag2_transport/reader_writer_factory.hpp" #include "logging.hpp" @@ -1543,7 +1544,7 @@ Player::Player(const std::string & node_name, const rclcpp::NodeOptions & node_o keyboard_handler = std::make_shared(); } - auto reader = std::make_unique(); + auto reader = ReaderWriterFactory::make_reader(storage_options); pimpl_ = std::make_unique( this, std::move(reader), keyboard_handler, storage_options, play_options); diff --git a/rosbag2_transport/src/rosbag2_transport/recorder.cpp b/rosbag2_transport/src/rosbag2_transport/recorder.cpp index 212cf9c99..d5d1f0b0e 100644 --- a/rosbag2_transport/src/rosbag2_transport/recorder.cpp +++ b/rosbag2_transport/src/rosbag2_transport/recorder.cpp @@ -42,6 +42,7 @@ #include "logging.hpp" #include "rosbag2_transport/config_options_from_node_params.hpp" +#include "rosbag2_transport/reader_writer_factory.hpp" #include "rosbag2_transport/topic_filter.hpp" namespace rosbag2_transport @@ -756,7 +757,7 @@ Recorder::Recorder( keyboard_handler = std::make_shared(); } - auto writer = std::make_unique(); + auto writer = ReaderWriterFactory::make_writer(record_options); pimpl_ = std::make_unique( this, std::move(writer), keyboard_handler, diff --git a/rosbag2_transport/test/resources/recorder_node_params.yaml b/rosbag2_transport/test/resources/recorder_node_params.yaml index 771f80539..701f623bf 100644 --- a/rosbag2_transport/test/resources/recorder_node_params.yaml +++ b/rosbag2_transport/test/resources/recorder_node_params.yaml @@ -20,8 +20,8 @@ recorder_params_node: exclude_topics: ["exclude_topic", "other_exclude_topic"] exclude_services: ["exclude_service", "other_exclude_service"] node_prefix: "prefix" - compression_mode: "stream" - compression_format: "h264" + compression_mode: "file" + compression_format: "zstd" compression_queue_size: 10 compression_threads: 2 compression_threads_priority: -1 diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp index f1e828a23..97a89bc5a 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp @@ -230,8 +230,8 @@ TEST_P(ComposableRecorderTests, recorder_can_parse_parameters_from_file) { "/exclude_service/_service_event", "/other_exclude_service/_service_event"}; EXPECT_EQ(record_options.exclude_service_events, exclude_services); EXPECT_EQ(record_options.node_prefix, "prefix"); - EXPECT_EQ(record_options.compression_mode, "stream"); - EXPECT_EQ(record_options.compression_format, "h264"); + EXPECT_EQ(record_options.compression_mode, "file"); + EXPECT_EQ(record_options.compression_format, "zstd"); EXPECT_EQ(record_options.compression_queue_size, 10); EXPECT_EQ(record_options.compression_threads, 2); EXPECT_EQ(record_options.compression_threads_priority, -1);