From 1a9f7024601aa72958a7c089eb48ac0138cad399 Mon Sep 17 00:00:00 2001 From: Ryan Pennings Date: Sun, 31 Jul 2022 16:40:53 +1000 Subject: [PATCH] fixed limit on pcl range cutoff --- src/laserscan_multi_merger.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/laserscan_multi_merger.cpp b/src/laserscan_multi_merger.cpp index 3f05b81..61dc480 100644 --- a/src/laserscan_multi_merger.cpp +++ b/src/laserscan_multi_merger.cpp @@ -216,7 +216,7 @@ void LaserscanMerger::scanCallback(sensor_msgs::msg::LaserScan::SharedPtr scan, { // Verify that TF knows how to transform from the received scan to the destination scan frame tf_buffer_->lookupTransform(scan->header.frame_id.c_str(), destination_frame.c_str(), scan->header.stamp, rclcpp::Duration(1, 0)); - projector_.transformLaserScanToPointCloud(scan->header.frame_id, *scan, tmpCloud1, *tf_buffer_, laser_geometry::channel_option::Distance); + projector_.transformLaserScanToPointCloud(scan->header.frame_id, *scan, tmpCloud1, *tf_buffer_, range_max); pcl_ros::transformPointCloud(destination_frame.c_str(), tmpCloud1, tmpCloud2, *tf_buffer_); } catch (tf2::TransformException &ex)