From 6c597d3310e4f2884705afe9b2793d30f45ee017 Mon Sep 17 00:00:00 2001 From: pradyum Date: Tue, 12 Nov 2024 08:16:52 +0530 Subject: [PATCH] fixed conflict --- src/dual_laser_merger.cpp | 23 ++++++----------------- 1 file changed, 6 insertions(+), 17 deletions(-) diff --git a/src/dual_laser_merger.cpp b/src/dual_laser_merger.cpp index 9a213a9..9361cdf 100644 --- a/src/dual_laser_merger.cpp +++ b/src/dual_laser_merger.cpp @@ -29,29 +29,18 @@ MergerNode::MergerNode(const rclcpp::NodeOptions & options) RCLCPP_INFO(this->get_logger(), "Target Frame: %s", target_frame_param.c_str()); } -<<<<<<< HEAD - merged_pub = - this->create_publisher( - this->get_parameter( - "merged_topic").as_string(), rclcpp::SensorDataQoS()); - laser_1_sub.subscribe( - this, this->get_parameter("laser_1_topic").as_string(), - rclcpp::SensorDataQoS().get_rmw_qos_profile()); - laser_2_sub.subscribe( - this, this->get_parameter("laser_2_topic").as_string(), - rclcpp::SensorDataQoS().get_rmw_qos_profile()); -======= merged_scan_pub = this->create_publisher(this->get_parameter( "merged_scan_topic").as_string(), rclcpp::SensorDataQoS()); merged_cloud_pub = this->create_publisher(this->get_parameter( "merged_cloud_topic").as_string(), rclcpp::SensorDataQoS()); - laser_1_sub.subscribe(this, this->get_parameter("laser_1_topic").as_string(), - rclcpp::SensorDataQoS()); - laser_2_sub.subscribe(this, this->get_parameter("laser_2_topic").as_string(), - rclcpp::SensorDataQoS()); ->>>>>>> 208df64 (added shadow and average filters) + laser_1_sub.subscribe( + this, this->get_parameter("laser_1_topic").as_string(), + rclcpp::SensorDataQoS().get_rmw_qos_profile()); + laser_2_sub.subscribe( + this, this->get_parameter("laser_2_topic").as_string(), + rclcpp::SensorDataQoS().get_rmw_qos_profile()); tf2_buffer = std::make_shared(this->get_clock()); tf2_listener = std::make_shared(*tf2_buffer, this);