We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent d29390a commit 288db04Copy full SHA for 288db04
simulator/dummy_perception_publisher/src/node.cpp
@@ -180,7 +180,9 @@ void DummyPerceptionPublisherNode::timerCallback()
180
new pcl::PointCloud<pcl::PointXYZ>);
181
pcl::VoxelGridOcclusionEstimation<pcl::PointXYZ> ray_tracing_filter;
182
ray_tracing_filter.setInputCloud(merged_pointcloud_ptr);
183
- ray_tracing_filter.setLeafSize(0.25, 0.25, 0.25);
+ // above this value raytrace won't be as expected
184
+ const double leaf_size = 0.02;
185
+ ray_tracing_filter.setLeafSize(leaf_size, leaf_size, leaf_size);
186
ray_tracing_filter.initializeVoxelGrid();
187
for (size_t i = 0; i < v_pointcloud.size(); ++i) {
188
pcl::PointCloud<pcl::PointXYZ>::Ptr ray_traced_pointcloud_ptr(
0 commit comments