Skip to content

Commit

Permalink
fix(compare_map_segmentation): keep low level pointcloud
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
  • Loading branch information
badai-nguyen committed Jul 11, 2023
1 parent 3ae0b00 commit eb07f95
Showing 1 changed file with 0 additions and 50 deletions.
50 changes: 0 additions & 50 deletions perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,11 +76,6 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
pcl::PointXYZ(point.x, point.y, point.z), point, distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x, point.y - distance_threshold, point.z - distance_threshold), point,
distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x, point.y - distance_threshold, point.z), point, distance_threshold,
map, voxel)) {
Expand All @@ -91,21 +86,11 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x, point.y, point.z - distance_threshold), point, distance_threshold,
map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x, point.y, point.z + distance_threshold), point, distance_threshold,
map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x, point.y + distance_threshold, point.z - distance_threshold), point,
distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x, point.y + distance_threshold, point.z), point, distance_threshold,
map, voxel)) {
Expand All @@ -116,13 +101,6 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
distance_threshold, map, voxel)) {
return true;
}

if (is_in_voxel(
pcl::PointXYZ(
point.x - distance_threshold, point.y - distance_threshold, point.z - distance_threshold),
point, distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x - distance_threshold, point.y - distance_threshold, point.z), point,
distance_threshold, map, voxel)) {
Expand All @@ -134,11 +112,6 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
point, distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x - distance_threshold, point.y, point.z - distance_threshold), point,
distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x - distance_threshold, point.y, point.z), point, distance_threshold,
map, voxel)) {
Expand All @@ -149,12 +122,6 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(
point.x - distance_threshold, point.y + distance_threshold, point.z - distance_threshold),
point, distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x - distance_threshold, point.y + distance_threshold, point.z), point,
distance_threshold, map, voxel)) {
Expand All @@ -167,12 +134,6 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
return true;
}

if (is_in_voxel(
pcl::PointXYZ(
point.x + distance_threshold, point.y - distance_threshold, point.z - distance_threshold),
point, distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x + distance_threshold, point.y - distance_threshold, point.z), point,
distance_threshold, map, voxel)) {
Expand All @@ -184,11 +145,6 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
point, distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x + distance_threshold, point.y, point.z - distance_threshold), point,
distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x + distance_threshold, point.y, point.z), point, distance_threshold,
map, voxel)) {
Expand All @@ -199,12 +155,6 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(
point.x + distance_threshold, point.y + distance_threshold, point.z - distance_threshold),
point, distance_threshold, map, voxel)) {
return true;
}
if (is_in_voxel(
pcl::PointXYZ(point.x + distance_threshold, point.y + distance_threshold, point.z), point,
distance_threshold, map, voxel)) {
Expand Down

0 comments on commit eb07f95

Please sign in to comment.