diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp index 8617fee44a787..228dfc4f8f459 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -21,7 +21,12 @@ #include #include #include + +#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER #include +#else +#include +#endif #define EIGEN_MPL2_ONLY #include @@ -165,7 +170,7 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( // Create Kd-tree to search neighbor pointcloud to reduce cost. pcl::search::Search::Ptr kdtree = - boost::make_shared>(false); + pcl::make_shared>(false); kdtree->setInputCloud(obstacle_pointcloud); for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { diff --git a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp index d8542d62fc469..92a9679cc3f27 100644 --- a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp +++ b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp @@ -18,7 +18,11 @@ #include +#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER #include +#else +#include +#endif #define EIGEN_MPL2_ONLY #include