Skip to content

Commit

Permalink
fixed conflict
Browse files Browse the repository at this point in the history
  • Loading branch information
pradyum committed Nov 12, 2024
1 parent eac5724 commit 6c597d3
Showing 1 changed file with 6 additions and 17 deletions.
23 changes: 6 additions & 17 deletions src/dual_laser_merger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<sensor_msgs::msg::LaserScan>(
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<sensor_msgs::msg::LaserScan>(this->get_parameter(
"merged_scan_topic").as_string(), rclcpp::SensorDataQoS());
merged_cloud_pub =
this->create_publisher<sensor_msgs::msg::PointCloud2>(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<tf2_ros::Buffer>(this->get_clock());
tf2_listener = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer, this);
Expand Down

0 comments on commit 6c597d3

Please sign in to comment.