diff --git a/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.cpp index 73390abae7301..848cc4606b230 100644 --- a/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.cpp @@ -29,9 +29,7 @@ #include #include // To be replaced by std::filesystem in C++17 -#include #include -#include namespace autoware::compare_map_segmentation { diff --git a/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.hpp b/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.hpp index ceddaa67ac2cd..8e5015ef21ef7 100644 --- a/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.hpp +++ b/perception/autoware_compare_map_segmentation/src/compare_elevation_map_filter/node.hpp @@ -24,11 +24,7 @@ #include -#include -#include -#include #include -#include namespace autoware::compare_map_segmentation { class CompareElevationMapFilterComponent : public autoware::pointcloud_preprocessor::Filter diff --git a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp index 8b44d1661da48..a2e3afd62cdad 100644 --- a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp @@ -51,10 +51,10 @@ bool DistanceBasedStaticMapLoader::is_close_to_map( if (!is_initialized_.load(std::memory_order_acquire)) { return false; } - if (map_ptr_ == NULL) { + if (map_ptr_ == nullptr) { return false; } - if (tree_ == NULL) { + if (tree_ == nullptr) { return false; } @@ -89,8 +89,8 @@ bool DistanceBasedDynamicMapLoader::is_close_to_map( if (static_cast(map_grid_index) >= current_voxel_grid_array_.size()) { return false; } - if (current_voxel_grid_array_.at(map_grid_index) != NULL) { - if (current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree == NULL) { + if (current_voxel_grid_array_.at(map_grid_index) != nullptr) { + if (current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree == nullptr) { return false; } std::vector nn_indices(1); 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 509303c3a4e0e..d6b65daa82267 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 @@ -24,14 +24,13 @@ #include #include -#include namespace autoware::compare_map_segmentation { -typedef typename pcl::Filter::PointCloud PointCloud; -typedef typename PointCloud::Ptr PointCloudPtr; -typedef typename PointCloud::ConstPtr PointCloudConstPtr; +using PointCloud = typename pcl::Filter::PointCloud; +using PointCloudPtr = typename PointCloud::Ptr; +using PointCloudConstPtr = typename PointCloud::ConstPtr; class DistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader { @@ -102,8 +101,8 @@ class DistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader class DistanceBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: - virtual void filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); + void filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; private: double distance_threshold_; diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp index 7ffb825910f64..a02a6865ef9ef 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp @@ -29,7 +29,7 @@ namespace autoware::compare_map_segmentation bool VoxelBasedApproximateStaticMapLoader::is_close_to_map( const pcl::PointXYZ & point, [[maybe_unused]] const double distance_threshold) { - if (voxel_map_ptr_ == NULL) { + if (voxel_map_ptr_ == nullptr) { return false; } const int index = @@ -55,7 +55,7 @@ bool VoxelBasedApproximateDynamicMapLoader::is_close_to_map( if (static_cast(map_grid_index) >= current_voxel_grid_array_.size()) { return false; } - if (current_voxel_grid_array_.at(map_grid_index) != NULL) { + if (current_voxel_grid_array_.at(map_grid_index) != nullptr) { const int index = current_voxel_grid_array_.at(map_grid_index) ->map_cell_voxel_grid.getCentroidIndexAt( current_voxel_grid_array_.at(map_grid_index) diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp index c8ad7c16f59cb..1cbf9c0571b73 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp @@ -23,7 +23,6 @@ #include #include -#include namespace autoware::compare_map_segmentation { @@ -59,8 +58,8 @@ class VoxelBasedApproximateCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: - virtual void filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); + void filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; private: double distance_threshold_; diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp index e024d2b538e51..cdad52b5a278d 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp @@ -22,11 +22,9 @@ #include #include -#include namespace autoware::compare_map_segmentation { -using autoware::pointcloud_preprocessor::get_param; VoxelBasedCompareMapFilterComponent::VoxelBasedCompareMapFilterComponent( const rclcpp::NodeOptions & options) diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp index ac81eae85b8a0..ba29f9ac25af0 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp @@ -22,15 +22,14 @@ #include #include -#include namespace autoware::compare_map_segmentation { class VoxelBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: - virtual void filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); + void filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; private: // pcl::SegmentDifferences impl_; @@ -39,8 +38,6 @@ class VoxelBasedCompareMapFilterComponent : public autoware::pointcloud_preproce double distance_threshold_; bool set_map_in_voxel_grid_; - bool dynamic_map_load_enable_; - public: PCL_MAKE_ALIGNED_OPERATOR_NEW explicit VoxelBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options); diff --git a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp index 62f126c0039f4..291a19d02ed4b 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp @@ -61,13 +61,13 @@ bool VoxelDistanceBasedStaticMapLoader::is_close_to_map( if (!is_initialized_.load(std::memory_order_acquire)) { return false; } - if (voxel_map_ptr_ == NULL) { + if (voxel_map_ptr_ == nullptr) { return false; } - if (map_ptr_ == NULL) { + if (map_ptr_ == nullptr) { return false; } - if (tree_ == NULL) { + if (tree_ == nullptr) { return false; } if (is_close_to_neighbor_voxels(point, distance_threshold, voxel_grid_, tree_)) { @@ -91,7 +91,7 @@ bool VoxelDistanceBasedDynamicMapLoader::is_close_to_map( return false; } if ( - current_voxel_grid_array_.at(map_grid_index) != NULL && + current_voxel_grid_array_.at(map_grid_index) != nullptr && is_close_to_neighbor_voxels( point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid, current_voxel_grid_array_.at(map_grid_index)->map_cell_kdtree)) { 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 015ee52793768..218f19601cd41 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 @@ -25,14 +25,13 @@ #include #include #include -#include namespace autoware::compare_map_segmentation { -typedef typename pcl::Filter::PointCloud PointCloud; -typedef typename PointCloud::Ptr PointCloudPtr; -typedef typename PointCloud::ConstPtr PointCloudConstPtr; +using PointCloud = typename pcl::Filter::PointCloud; +using PointCloudPtr = typename PointCloud::Ptr; +using PointCloudConstPtr = typename PointCloud::ConstPtr; class VoxelDistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader { @@ -124,8 +123,8 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader class VoxelDistanceBasedCompareMapFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: - virtual void filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); + void filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; void input_target_callback(const PointCloud2ConstPtr map); 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 2627bbff64866..6e927db4e298b 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 @@ -47,7 +47,7 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels( if (index != -1) { return true; } - if (tree == NULL) { + if (tree == nullptr) { return false; } std::vector nn_indices(1); @@ -64,7 +64,7 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels( { // check map downsampled pc double distance_threshold_z = downsize_ratio_z_axis_ * distance_threshold; - if (map == NULL) { + if (map == nullptr) { return false; } if (is_in_voxel( @@ -331,7 +331,7 @@ bool VoxelGridDynamicMapLoader::is_close_to_next_map_grid( if ( static_cast(neighbor_map_grid_index) >= current_voxel_grid_array_.size() || neighbor_map_grid_index == current_map_grid_index || - current_voxel_grid_array_.at(neighbor_map_grid_index) != NULL) { + current_voxel_grid_array_.at(neighbor_map_grid_index) != nullptr) { return false; } if (is_close_to_neighbor_voxels( @@ -360,7 +360,7 @@ bool VoxelGridDynamicMapLoader::is_close_to_map( return false; } if ( - current_voxel_grid_array_.at(map_grid_index) != NULL && + current_voxel_grid_array_.at(map_grid_index) != nullptr && is_close_to_neighbor_voxels( point, distance_threshold, current_voxel_grid_array_.at(map_grid_index)->map_cell_pc_ptr, current_voxel_grid_array_.at(map_grid_index)->map_cell_voxel_grid)) { 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 f50d23d4af6e8..b24286874801f 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 @@ -30,7 +30,6 @@ #include #include #include -#include #include #include @@ -93,13 +92,15 @@ class VoxelGridMapLoader bool debug_ = false; public: - typedef VoxelGridEx VoxelGridPointXYZ; - typedef typename pcl::Filter::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; + using VoxelGridPointXYZ = VoxelGridEx; + using PointCloud = typename pcl::Filter::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; explicit VoxelGridMapLoader( rclcpp::Node * node, double leaf_size, double downsize_ratio_z_axis, std::string * tf_map_input_frame); + virtual ~VoxelGridMapLoader() = default; + virtual bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) = 0; static bool is_close_to_neighbor_voxels( const pcl::PointXYZ & point, const double distance_threshold, VoxelGridPointXYZ & voxel, @@ -142,7 +143,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader pcl::search::Search::Ptr map_cell_kdtree; }; - typedef typename std::map VoxelGridDict; + using VoxelGridDict = typename std::map; /** \brief Map to hold loaded map grid id and it's voxel filter */ VoxelGridDict current_voxel_grid_dict_; diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 247a8faf6b13a..56dab521d7dff 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -36,6 +36,7 @@ target_include_directories(pointcloud_preprocessor_filter_base PUBLIC ) ament_target_dependencies(pointcloud_preprocessor_filter_base + SYSTEM message_filters pcl_conversions rclcpp @@ -56,6 +57,7 @@ target_include_directories(faster_voxel_grid_downsample_filter PUBLIC ) ament_target_dependencies(faster_voxel_grid_downsample_filter + SYSTEM pcl_conversions rclcpp sensor_msgs