Skip to content

Commit ec3ee28

Browse files
committed
fix: pointcloud_octomap_updater not cleaning objects at max_range
1 parent 2302268 commit ec3ee28

File tree

1 file changed

+1
-0
lines changed

1 file changed

+1
-0
lines changed

moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -338,6 +338,7 @@ void PointCloudOctomapUpdater::cloudMsgCallback(const sensor_msgs::msg::PointClo
338338
/* compute the free cells along each ray that ends at a clipped cell */
339339
for (const octomap::OcTreeKey& clip_cell : clip_cells)
340340
{
341+
free_cells.insert(clip_cell);
341342
if (tree_->computeRayKeys(sensor_origin, tree_->keyToCoord(clip_cell), key_ray_))
342343
free_cells.insert(key_ray_.begin(), key_ray_.end());
343344
}

0 commit comments

Comments
 (0)