diff --git a/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid.hpp b/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid.hpp index d3ae763ffe4bf..670e58fb936cc 100644 --- a/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid.hpp +++ b/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid.hpp @@ -51,7 +51,12 @@ #ifndef TIER4_PCL_EXTENSIONS__VOXEL_GRID_NEAREST_CENTROID_HPP_ #define TIER4_PCL_EXTENSIONS__VOXEL_GRID_NEAREST_CENTROID_HPP_ +#include + +#if PCL_VERSION < PCL_VERSION_CALC(1, 12, 0) #include +#endif + #include #include #include @@ -97,8 +102,8 @@ class VoxelGridNearestCentroid : public VoxelGrid typedef typename PointCloud::ConstPtr PointCloudConstPtr; public: - typedef boost::shared_ptr> Ptr; - typedef boost::shared_ptr> ConstPtr; + typedef pcl::shared_ptr> Ptr; + typedef pcl::shared_ptr> ConstPtr; /** \brief Simple structure to hold a centroid, covariance and the number of points in a leaf. * Inverse covariance, eigen vectors and eigen values are precomputed. */ diff --git a/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp b/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp index 84ebacf4e57ed..5a8a8c3619cdd 100644 --- a/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp +++ b/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp @@ -57,7 +57,11 @@ #include #include +#include + +#if PCL_VERSION < PCL_VERSION_CALC(1, 12, 0) #include +#endif #include #include