Skip to content
Draft
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
39 changes: 35 additions & 4 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2167,7 +2167,17 @@ Player::Player(
const rclcpp::NodeOptions & node_options)
: rclcpp::Node(
node_name,
rclcpp::NodeOptions(node_options).arguments(play_options.topic_remapping_options))
// Merge existing arguments with topic remapping options
rclcpp::NodeOptions(node_options).arguments(
[&, node_options]() {
auto args = node_options.arguments();
args.insert(args.end(),
play_options.topic_remapping_options.begin(),
play_options.topic_remapping_options.end());
return args;
}()
)
)
{
Comment on lines +2172 to 2181
Copy link

Copilot AI Jul 15, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The identical lambda logic is duplicated across three constructors. Consider extracting this into a private helper function to improve maintainability and reduce code duplication.

Suggested change
[&, node_options]() {
auto args = node_options.arguments();
args.insert(args.end(),
play_options.topic_remapping_options.begin(),
play_options.topic_remapping_options.end());
return args;
}()
)
)
{
merge_node_arguments(node_options, play_options)
)
)
{
// Helper function for merging node arguments
auto merge_node_arguments(
const rclcpp::NodeOptions & node_options,
const rosbag2_transport::PlayOptions & play_options) -> std::vector<std::string> {
auto args = node_options.arguments();
args.insert(args.end(),
play_options.topic_remapping_options.begin(),
play_options.topic_remapping_options.end());
return args;
}

Copilot uses AI. Check for mistakes.
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

hmm i do not think this is necessary. waiting for what other people think about this.

std::shared_ptr<KeyboardHandler> keyboard_handler;
if (!play_options.disable_keyboard_controls) {
Expand Down Expand Up @@ -2202,7 +2212,17 @@ Player::Player(
const rclcpp::NodeOptions & node_options)
: rclcpp::Node(
node_name,
rclcpp::NodeOptions(node_options).arguments(play_options.topic_remapping_options))
// Merge existing arguments with topic remapping options
rclcpp::NodeOptions(node_options).arguments(
[&, node_options]() {
auto args = node_options.arguments();
args.insert(args.end(),
play_options.topic_remapping_options.begin(),
play_options.topic_remapping_options.end());
return args;
}()
)
)
{
std::vector<reader_storage_options_pair_t> readers_with_options{};
readers_with_options.emplace_back(std::move(reader), storage_options);
Expand Down Expand Up @@ -2231,10 +2251,21 @@ Player::Player(
const rclcpp::NodeOptions & node_options)
: rclcpp::Node(
node_name,
rclcpp::NodeOptions(node_options).arguments(play_options.topic_remapping_options)),
// Merge existing arguments with topic remapping options
rclcpp::NodeOptions(node_options).arguments(
[&, node_options]() {
auto args = node_options.arguments();
args.insert(args.end(),
play_options.topic_remapping_options.begin(),
play_options.topic_remapping_options.end());
return args;
}()
)
),
pimpl_(std::make_unique<PlayerImpl>(
this, std::move(readers_with_options), std::move(keyboard_handler), play_options))
{}
{
}
Comment on lines +2267 to +2268
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this change is unrelated but i met the following error to be fixed with it.

135: Test command: /usr/bin/python3 "-u" "/root/ros2_ws/colcon_ws/install/ament_cmake_test/share/ament_cmake_test/cmake/run_test.py" "/root/ros2_ws/colcon_ws/build/rosbag2_transport/test_results/rosbag2_transport/uncrustify.xunit.xml" "--package-name" "rosbag2_transport" "--output-file" "/root/ros2_ws/colcon_ws/build/rosbag2_transport/ament_uncrustify/uncrustify.txt" "--command" "/root/ros2_ws/colcon_ws/install/ament_uncrustify/bin/ament_uncrustify" "--xunit-file" "/root/ros2_ws/colcon_ws/build/rosbag2_transport/test_results/rosbag2_transport/uncrustify.xunit.xml"
135: Working Directory: /root/ros2_ws/colcon_ws/src/ros2/rosbag2/rosbag2_transport
135: Test timeout computed to be: 60
135: -- run_test.py: invoking following command in '/root/ros2_ws/colcon_ws/src/ros2/rosbag2/rosbag2_transport':
135:  - /root/ros2_ws/colcon_ws/install/ament_uncrustify/bin/ament_uncrustify --xunit-file /root/ros2_ws/colcon_ws/build/rosbag2_transport/test_results/rosbag2_transport/uncrustify.xunit.xml
135: Code style divergence in file 'src/rosbag2_transport/player.cpp':
135:
135: --- src/rosbag2_transport/player.cpp
135: +++ src/rosbag2_transport/player.cpp.uncrustify
135: @@ -2180 +2180 @@
135: -  )
135: +)
135: @@ -2225 +2225 @@
135: -  )
135: +)
135: @@ -2264 +2264 @@
135: -  ),
135: +),
135: @@ -2267 +2267,2 @@
135: -{}
135: +{
135: +}
135:
135: 1 files with code style divergence


Player::~Player() = default;

Expand Down
Loading