diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index 3cb9c07e45008..cec59173a2e7d 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -23,6 +23,7 @@ include_directories( ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/filter.cpp + src/utility/utilities.cpp src/concatenate_data/concatenate_data_nodelet.cpp src/crop_box_filter/crop_box_filter_nodelet.cpp src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/no_detection_area_filter/no_detection_area_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/no_detection_area_filter/no_detection_area_filter.hpp index c02e41a1babe0..ec30907924ebf 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/no_detection_area_filter/no_detection_area_filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/no_detection_area_filter/no_detection_area_filter.hpp @@ -16,6 +16,7 @@ #define POINTCLOUD_PREPROCESSOR__NO_DETECTION_AREA_FILTER__NO_DETECTION_AREA_FILTER_HPP_ #include "pointcloud_preprocessor/filter.hpp" +#include "pointcloud_preprocessor/utility/utilities.hpp" #include #include diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp index 91d2875ac2afc..36668f6a45bd3 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp @@ -16,6 +16,7 @@ #define POINTCLOUD_PREPROCESSOR__POLYGON_REMOVER__POLYGON_REMOVER_HPP_ #include "pointcloud_preprocessor/filter.hpp" +#include "pointcloud_preprocessor/utility/utilities.hpp" #include #include diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/utilities.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/utilities.hpp new file mode 100644 index 0000000000000..d28b90bce185a --- /dev/null +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/utility/utilities.hpp @@ -0,0 +1,62 @@ +// Copyright 2022 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef POINTCLOUD_PREPROCESSOR__UTILITY__UTILITIES_HPP_ +#define POINTCLOUD_PREPROCESSOR__UTILITY__UTILITIES_HPP_ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +using K = CGAL::Exact_predicates_inexact_constructions_kernel; +using PointCgal = K::Point_2; + +namespace pointcloud_preprocessor::utils +{ +/** + * @brief convert ROS polygon to CGAL polygon + */ +std::vector to_cgal_polygon( + const geometry_msgs::msg::Polygon::ConstSharedPtr & polygon_in); + +/** + * @brief convert lanelet polygon to CGAL polygon + */ +std::vector to_cgal_polygon(const lanelet::BasicPolygon2d & polygon_in); + +/** + * @brief remove points in the given polygon + */ +sensor_msgs::msg::PointCloud2 remove_polygon_cgal_from_cloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud_in_ptr, + const std::vector & polyline_polygon); + +/** + * @brief remove points in the given polygon + */ +pcl::PointCloud remove_polygon_cgal_from_cloud( + const pcl::PointCloud & cloud_in, const std::vector & polyline_polygon); + +} // namespace pointcloud_preprocessor::utils + +#endif // POINTCLOUD_PREPROCESSOR__UTILITY__UTILITIES_HPP_ diff --git a/sensing/pointcloud_preprocessor/src/no_detection_area_filter/no_detection_area_filter.cpp b/sensing/pointcloud_preprocessor/src/no_detection_area_filter/no_detection_area_filter.cpp index 5805c8e5c80c7..1b717339bac75 100644 --- a/sensing/pointcloud_preprocessor/src/no_detection_area_filter/no_detection_area_filter.cpp +++ b/sensing/pointcloud_preprocessor/src/no_detection_area_filter/no_detection_area_filter.cpp @@ -18,17 +18,6 @@ namespace { -bool pointWithinLanelets(const Point2d & point, const lanelet::ConstPolygons3d & lanelets) -{ - for (const auto & lanelet : lanelets) { - if (boost::geometry::within(point, lanelet::utils::to2D(lanelet).basicPolygon())) { - return true; - } - } - - return false; -} - tier4_autoware_utils::Box2d calcBoundingBox( const pcl::PointCloud::ConstPtr & input_cloud) { @@ -53,17 +42,15 @@ lanelet::ConstPolygons3d calcIntersectedPolygons( } pcl::PointCloud removePointsWithinPolygons( - const lanelet::ConstPolygons3d & polygons, const pcl::PointCloud::Ptr & cloud) + const pcl::PointCloud::Ptr & cloud_in, const lanelet::ConstPolygons3d & polygons) { - pcl::PointCloud filtered_cloud; - filtered_cloud.header = cloud->header; - - for (const auto & p : cloud->points) { - if (pointWithinLanelets(Point2d(p.x, p.y), polygons)) { - continue; - } + pcl::PointCloud filtered_cloud = *cloud_in; - filtered_cloud.points.push_back(p); + for (const auto & polygon : polygons) { + const auto lanelet_poly = lanelet::utils::to2D(polygon).basicPolygon(); + const auto cgal_poly = pointcloud_preprocessor::utils::to_cgal_polygon(lanelet_poly); + filtered_cloud = + pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud(filtered_cloud, cgal_poly); } return filtered_cloud; @@ -108,7 +95,7 @@ void NoDetectionAreaFilterComponent::filter( calcIntersectedPolygons(bounding_box, no_detection_area_lanelets_); // filter pointcloud by lanelet - const auto filtered_pc = removePointsWithinPolygons(intersected_lanelets, pc_input); + const auto filtered_pc = removePointsWithinPolygons(pc_input, intersected_lanelets); // convert to ROS message pcl::toROSMsg(filtered_pc, output); diff --git a/sensing/pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp b/sensing/pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp index b88ba9c7f71fc..61782464f06b0 100644 --- a/sensing/pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp +++ b/sensing/pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp @@ -70,7 +70,7 @@ void PolygonRemoverComponent::filter( void PolygonRemoverComponent::update_polygon( const geometry_msgs::msg::Polygon::ConstSharedPtr & polygon_in) { - polygon_cgal_ = polygon_geometry_to_cgal(polygon_in); + polygon_cgal_ = pointcloud_preprocessor::utils::to_cgal_polygon(polygon_in); if (will_visualize_) { marker_.ns = ""; marker_.id = 0; @@ -131,49 +131,7 @@ sensor_msgs::msg::PointCloud2 PolygonRemoverComponent::remove_updated_polygon_fr throw std::runtime_error("Polygon is not initialized. Please use `update_polygon` first."); } - return remove_polygon_cgal_from_cloud(cloud_in, polygon_cgal_); -} - -sensor_msgs::msg::PointCloud2 PolygonRemoverComponent::remove_polygon_cgal_from_cloud( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud_in_ptr, - const std::vector & polyline_polygon) -{ - sensor_msgs::msg::PointCloud2 output; - pcl::PointCloud pcl_output; - - sensor_msgs::msg::PointCloud2 transformed_cluster = *cloud_in_ptr; - - for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), - iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); - iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { - if ( - CGAL::bounded_side_2( - polyline_polygon.begin(), polyline_polygon.end(), PointCgal(*iter_x, *iter_y), K()) == - CGAL::ON_UNBOUNDED_SIDE) { - pcl::PointXYZ p; - p.x = *iter_x; - p.y = *iter_y; - p.z = *iter_z; - pcl_output.emplace_back(p); - } - } - pcl::toROSMsg(pcl_output, output); - output.header = cloud_in_ptr->header; - return output; -} -std::vector PolygonRemoverComponent::polygon_geometry_to_cgal( - const geometry_msgs::msg::Polygon::ConstSharedPtr & polygon_in) -{ - std::vector polyline_polygon; - if (polygon_in->points.size() < 3) { - throw std::length_error("Polygon vertex count should be larger than 2."); - } - const auto & vertices_in = polygon_in->points; - polyline_polygon.resize(vertices_in.size()); - std::transform( - polygon_in->points.begin(), polygon_in->points.end(), polyline_polygon.begin(), - [](const geometry_msgs::msg::Point32 & p_in) { return PointCgal(p_in.x, p_in.y); }); - return polyline_polygon; + return pointcloud_preprocessor::utils::remove_polygon_cgal_from_cloud(cloud_in, polygon_cgal_); } } // namespace pointcloud_preprocessor diff --git a/sensing/pointcloud_preprocessor/src/utility/utilities.cpp b/sensing/pointcloud_preprocessor/src/utility/utilities.cpp new file mode 100644 index 0000000000000..794f5cbe109c1 --- /dev/null +++ b/sensing/pointcloud_preprocessor/src/utility/utilities.cpp @@ -0,0 +1,97 @@ +// Copyright 2022 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pointcloud_preprocessor/utility/utilities.hpp" + +namespace pointcloud_preprocessor::utils +{ +std::vector to_cgal_polygon( + const geometry_msgs::msg::Polygon::ConstSharedPtr & polygon_in) +{ + std::vector polyline_polygon; + if (polygon_in->points.size() < 3) { + throw std::length_error("Polygon vertex count should be larger than 2."); + } + + const auto & vertices_in = polygon_in->points; + polyline_polygon.resize(vertices_in.size()); + std::transform( + polygon_in->points.begin(), polygon_in->points.end(), polyline_polygon.begin(), + [](const geometry_msgs::msg::Point32 & p_in) { return PointCgal(p_in.x, p_in.y); }); + return polyline_polygon; +} + +std::vector to_cgal_polygon(const lanelet::BasicPolygon2d & polygon_in) +{ + std::vector polyline_polygon; + if (polygon_in.size() < 3) { + throw std::length_error("Polygon vertex count should be larger than 2."); + } + + const auto & vertices_in = polygon_in; + polyline_polygon.resize(vertices_in.size()); + std::transform( + polygon_in.cbegin(), polygon_in.cend(), polyline_polygon.begin(), + [](const Eigen::Matrix & p_in) { return PointCgal(p_in.x(), p_in.y()); }); + return polyline_polygon; +} + +sensor_msgs::msg::PointCloud2 remove_polygon_cgal_from_cloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud_in_ptr, + const std::vector & polyline_polygon) +{ + sensor_msgs::msg::PointCloud2 output; + pcl::PointCloud pcl_output; + + sensor_msgs::msg::PointCloud2 transformed_cluster = *cloud_in_ptr; + + for (sensor_msgs::PointCloud2ConstIterator iter_x(transformed_cluster, "x"), + iter_y(transformed_cluster, "y"), iter_z(transformed_cluster, "z"); + iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { + // check if the point is inside the polygon + if ( + CGAL::bounded_side_2( + polyline_polygon.begin(), polyline_polygon.end(), PointCgal(*iter_x, *iter_y), K()) == + CGAL::ON_UNBOUNDED_SIDE) { + pcl::PointXYZ p; + p.x = *iter_x; + p.y = *iter_y; + p.z = *iter_z; + pcl_output.emplace_back(p); + } + } + pcl::toROSMsg(pcl_output, output); + output.header = cloud_in_ptr->header; + return output; +} + +pcl::PointCloud remove_polygon_cgal_from_cloud( + const pcl::PointCloud & cloud_in, const std::vector & polyline_polygon) +{ + pcl::PointCloud pcl_output; + + for (const auto & p : cloud_in) { + // check if the point is inside the polygon + if ( + CGAL::bounded_side_2( + polyline_polygon.begin(), polyline_polygon.end(), PointCgal(p.x, p.y), K()) == + CGAL::ON_UNBOUNDED_SIDE) { + pcl_output.emplace_back(p); + } + } + + return pcl_output; +} // namespace + +} // namespace pointcloud_preprocessor::utils