From c1d3478cd719b95d0fc9dcd2f064924253dedb40 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 5 Dec 2024 09:27:21 +0900 Subject: [PATCH] chore(compare_map_segmentation): rename defined type (#9181) Signed-off-by: badai-nguyen --- .../node.hpp | 8 +++---- .../node.hpp | 12 +++++------ .../voxel_grid_map_loader.cpp | 5 +++-- .../voxel_grid_map_loader.hpp | 21 ++++++++++--------- 4 files changed, 24 insertions(+), 22 deletions(-) diff --git a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp index d6b65daa82267..33c9d9ff3c788 100644 --- a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp +++ b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp @@ -28,14 +28,14 @@ namespace autoware::compare_map_segmentation { -using PointCloud = typename pcl::Filter::PointCloud; -using PointCloudPtr = typename PointCloud::Ptr; -using PointCloudConstPtr = typename PointCloud::ConstPtr; +using FilteredPointCloud = typename pcl::Filter::PointCloud; +using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; +using FilteredPointCloudConstPtr = typename FilteredPointCloud::ConstPtr; class DistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader { private: - PointCloudConstPtr map_ptr_; + FilteredPointCloudConstPtr map_ptr_; pcl::search::Search::Ptr tree_; public: diff --git a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp index 218f19601cd41..9fb81aa675655 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp @@ -29,14 +29,14 @@ namespace autoware::compare_map_segmentation { -using PointCloud = typename pcl::Filter::PointCloud; -using PointCloudPtr = typename PointCloud::Ptr; -using PointCloudConstPtr = typename PointCloud::ConstPtr; +using FilteredPointCloud = typename pcl::Filter::PointCloud; +using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; +using FilteredPointCloudConstPtr = typename FilteredPointCloud::ConstPtr; class VoxelDistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader { private: - PointCloudConstPtr map_ptr_; + FilteredPointCloudConstPtr map_ptr_; pcl::search::Search::Ptr tree_; public: @@ -55,7 +55,7 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader { protected: private: - PointCloudConstPtr map_ptr_; + FilteredPointCloudConstPtr map_ptr_; /* data */ public: explicit VoxelDistanceBasedDynamicMapLoader( @@ -78,7 +78,7 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp); VoxelGridPointXYZ map_cell_voxel_grid_tmp; - PointCloudPtr map_cell_downsampled_pc_ptr_tmp; + FilteredPointCloudPtr map_cell_downsampled_pc_ptr_tmp; auto map_cell_voxel_input_tmp_ptr = std::make_shared>(map_cell_pc_tmp); diff --git a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp index d55712f5b756e..e93b2097e583e 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp @@ -63,7 +63,7 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels( } bool VoxelGridMapLoader::is_close_to_neighbor_voxels( - const pcl::PointXYZ & point, const double distance_threshold, const PointCloudPtr & map, + const pcl::PointXYZ & point, const double distance_threshold, const FilteredPointCloudPtr & map, VoxelGridPointXYZ & voxel) const { // check map downsampled pc @@ -228,7 +228,8 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels( bool VoxelGridMapLoader::is_in_voxel( const pcl::PointXYZ & src_point, const pcl::PointXYZ & target_point, - const double distance_threshold, const PointCloudPtr & map, VoxelGridPointXYZ & voxel) const + const double distance_threshold, const FilteredPointCloudPtr & map, + VoxelGridPointXYZ & voxel) const { int voxel_index = voxel.getCentroidIndexAt(voxel.getGridCoordinates(src_point.x, src_point.y, src_point.z)); diff --git a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp index 7faabf2266291..3685008ffc4fe 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp @@ -54,9 +54,9 @@ class VoxelGridEx : public pcl::VoxelGrid using pcl::VoxelGrid::div_b_; using pcl::VoxelGrid::inverse_leaf_size_; - using PointCloud = typename pcl::Filter::PointCloud; - using PointCloudPtr = typename PointCloud::Ptr; - using PointCloudConstPtr = typename PointCloud::ConstPtr; + using FilteredPointCloud = typename pcl::Filter::PointCloud; + using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; + using FilteredPointCloudConstPtr = typename FilteredPointCloud::ConstPtr; public: using pcl::VoxelGrid::leaf_layout_; @@ -93,8 +93,8 @@ class VoxelGridMapLoader public: using VoxelGridPointXYZ = VoxelGridEx; - using PointCloud = typename pcl::Filter::PointCloud; - using PointCloudPtr = typename PointCloud::Ptr; + using FilteredPointCloud = typename pcl::Filter::PointCloud; + using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; explicit VoxelGridMapLoader( rclcpp::Node * node, double leaf_size, double downsize_ratio_z_axis, std::string * tf_map_input_frame); @@ -106,11 +106,12 @@ class VoxelGridMapLoader const pcl::PointXYZ & point, const double distance_threshold, VoxelGridPointXYZ & voxel, pcl::search::Search::Ptr tree); bool is_close_to_neighbor_voxels( - const pcl::PointXYZ & point, const double distance_threshold, const PointCloudPtr & map, + const pcl::PointXYZ & point, const double distance_threshold, const FilteredPointCloudPtr & map, VoxelGridPointXYZ & voxel) const; bool is_in_voxel( const pcl::PointXYZ & src_point, const pcl::PointXYZ & target_point, - const double distance_threshold, const PointCloudPtr & map, VoxelGridPointXYZ & voxel) const; + const double distance_threshold, const FilteredPointCloudPtr & map, + VoxelGridPointXYZ & voxel) const; void publish_downsampled_map(const pcl::PointCloud & downsampled_pc); std::string * tf_map_input_frame_; @@ -121,7 +122,7 @@ class VoxelGridStaticMapLoader : public VoxelGridMapLoader protected: rclcpp::Subscription::SharedPtr sub_map_; VoxelGridPointXYZ voxel_grid_; - PointCloudPtr voxel_map_ptr_; + FilteredPointCloudPtr voxel_map_ptr_; std::atomic_bool is_initialized_{false}; public: @@ -138,7 +139,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader struct MapGridVoxelInfo { VoxelGridPointXYZ map_cell_voxel_grid; - PointCloudPtr map_cell_pc_ptr; + FilteredPointCloudPtr map_cell_pc_ptr; float min_b_x, min_b_y, max_b_x, max_b_y; pcl::search::Search::Ptr map_cell_kdtree; }; @@ -291,7 +292,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp); VoxelGridPointXYZ map_cell_voxel_grid_tmp; - PointCloudPtr map_cell_downsampled_pc_ptr_tmp; + FilteredPointCloudPtr map_cell_downsampled_pc_ptr_tmp; auto map_cell_voxel_input_tmp_ptr = std::make_shared>(map_cell_pc_tmp);