Skip to content

Commit

Permalink
Bugfix for issue where unable to create composable nodes with compres…
Browse files Browse the repository at this point in the history
…sion (#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 <[email protected]>

* Address tests failures

Signed-off-by: Michael Orlov <[email protected]>

---------

Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov authored Jun 13, 2024
1 parent 8297cb0 commit 5062b6e
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 6 deletions.
3 changes: 2 additions & 1 deletion rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand Down Expand Up @@ -1543,7 +1544,7 @@ Player::Player(const std::string & node_name, const rclcpp::NodeOptions & node_o
keyboard_handler = std::make_shared<KeyboardHandler>();
}

auto reader = std::make_unique<rosbag2_cpp::Reader>();
auto reader = ReaderWriterFactory::make_reader(storage_options);

pimpl_ = std::make_unique<PlayerImpl>(
this, std::move(reader), keyboard_handler, storage_options, play_options);
Expand Down
3 changes: 2 additions & 1 deletion rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -756,7 +757,7 @@ Recorder::Recorder(
keyboard_handler = std::make_shared<KeyboardHandler>();
}

auto writer = std::make_unique<rosbag2_cpp::Writer>();
auto writer = ReaderWriterFactory::make_writer(record_options);

pimpl_ = std::make_unique<RecorderImpl>(
this, std::move(writer), keyboard_handler,
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_transport/test/resources/recorder_node_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit 5062b6e

Please sign in to comment.