diff --git a/simulator/dummy_perception_publisher/src/node.cpp b/simulator/dummy_perception_publisher/src/node.cpp index 3104369549a8a..7bdae277cb091 100644 --- a/simulator/dummy_perception_publisher/src/node.cpp +++ b/simulator/dummy_perception_publisher/src/node.cpp @@ -183,7 +183,9 @@ void DummyPerceptionPublisherNode::timerCallback() new pcl::PointCloud); pcl::VoxelGridOcclusionEstimation ray_tracing_filter; ray_tracing_filter.setInputCloud(merged_pointcloud_ptr); - ray_tracing_filter.setLeafSize(0.25, 0.25, 0.25); + // above this value raytrace won't be as expected + const double leaf_size = 0.02; + ray_tracing_filter.setLeafSize(leaf_size, leaf_size, leaf_size); ray_tracing_filter.initializeVoxelGrid(); for (size_t i = 0; i < v_pointcloud.size(); ++i) { pcl::PointCloud::Ptr ray_traced_pointcloud_ptr(