diff --git a/localization/ndt/CMakeLists.txt b/localization/ndt/CMakeLists.txt index ceaa9f6e9c0c1..e7542aee07cfb 100644 --- a/localization/ndt/CMakeLists.txt +++ b/localization/ndt/CMakeLists.txt @@ -46,6 +46,11 @@ target_include_directories(ndt $ ) +target_include_directories(ndt + SYSTEM PUBLIC + ${PCL_INCLUDE_DIRS} +) + ament_target_dependencies(ndt PUBLIC ndt_omp ndt_pcl_modified) # Can't use ament_target_dependencies() here because it doesn't link PCL # properly, see ndt_omp for more information. diff --git a/localization/ndt/include/ndt/base.hpp b/localization/ndt/include/ndt/base.hpp index f06e5d057f273..b81e7f1c57f6f 100644 --- a/localization/ndt/include/ndt/base.hpp +++ b/localization/ndt/include/ndt/base.hpp @@ -15,7 +15,7 @@ #ifndef NDT__BASE_HPP_ #define NDT__BASE_HPP_ -#include +#include #include #include #include @@ -30,8 +30,8 @@ class NormalDistributionsTransformBase virtual ~NormalDistributionsTransformBase() = default; virtual void align(pcl::PointCloud & output, const Eigen::Matrix4f & guess) = 0; - virtual void setInputTarget(const boost::shared_ptr> & map_ptr) = 0; - virtual void setInputSource(const boost::shared_ptr> & scan_ptr) = 0; + virtual void setInputTarget(const pcl::shared_ptr> & map_ptr) = 0; + virtual void setInputSource(const pcl::shared_ptr> & scan_ptr) = 0; virtual void setMaximumIterations(int max_iter) = 0; virtual void setResolution(float res) = 0; @@ -46,15 +46,15 @@ class NormalDistributionsTransformBase virtual double getTransformationProbability() const = 0; virtual double getNearestVoxelTransformationLikelihood() const = 0; virtual double getFitnessScore() = 0; - virtual boost::shared_ptr> getInputTarget() const = 0; - virtual boost::shared_ptr> getInputSource() const = 0; + virtual pcl::shared_ptr> getInputTarget() const = 0; + virtual pcl::shared_ptr> getInputSource() const = 0; virtual Eigen::Matrix4f getFinalTransformation() const = 0; virtual std::vector> getFinalTransformationArray() const = 0; virtual Eigen::Matrix getHessian() const = 0; - virtual boost::shared_ptr> getSearchMethodTarget() const = 0; + virtual pcl::shared_ptr> getSearchMethodTarget() const = 0; virtual double calculateTransformationProbability( const pcl::PointCloud & trans_cloud) const = 0; diff --git a/localization/ndt/include/ndt/impl/omp.hpp b/localization/ndt/include/ndt/impl/omp.hpp index 1308ec97d479f..353439332c76f 100644 --- a/localization/ndt/include/ndt/impl/omp.hpp +++ b/localization/ndt/include/ndt/impl/omp.hpp @@ -34,14 +34,14 @@ void NormalDistributionsTransformOMP::align( template void NormalDistributionsTransformOMP::setInputTarget( - const boost::shared_ptr> & map_ptr) + const pcl::shared_ptr> & map_ptr) { ndt_ptr_->setInputTarget(map_ptr); } template void NormalDistributionsTransformOMP::setInputSource( - const boost::shared_ptr> & scan_ptr) + const pcl::shared_ptr> & scan_ptr) { ndt_ptr_->setInputSource(scan_ptr); } @@ -122,14 +122,14 @@ double NormalDistributionsTransformOMP::getFitnessScor } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformOMP::getInputTarget() const { return ndt_ptr_->getInputTarget(); } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformOMP::getInputSource() const { return ndt_ptr_->getInputSource(); @@ -158,7 +158,7 @@ Eigen::Matrix NormalDistributionsTransformOMP -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformOMP::getSearchMethodTarget() const { return ndt_ptr_->getSearchMethodTarget(); diff --git a/localization/ndt/include/ndt/impl/pcl_generic.hpp b/localization/ndt/include/ndt/impl/pcl_generic.hpp index d05c946a459a4..329093cd28589 100644 --- a/localization/ndt/include/ndt/impl/pcl_generic.hpp +++ b/localization/ndt/include/ndt/impl/pcl_generic.hpp @@ -35,14 +35,14 @@ void NormalDistributionsTransformPCLGeneric::align( template void NormalDistributionsTransformPCLGeneric::setInputTarget( - const boost::shared_ptr> & map_ptr) + const pcl::shared_ptr> & map_ptr) { ndt_ptr_->setInputTarget(map_ptr); } template void NormalDistributionsTransformPCLGeneric::setInputSource( - const boost::shared_ptr> & scan_ptr) + const pcl::shared_ptr> & scan_ptr) { ndt_ptr_->setInputSource(scan_ptr); } @@ -125,14 +125,14 @@ double NormalDistributionsTransformPCLGeneric::getFitn } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformPCLGeneric::getInputTarget() const { return ndt_ptr_->getInputTarget(); } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformPCLGeneric::getInputSource() const { return ndt_ptr_->getInputSource(); @@ -162,7 +162,7 @@ NormalDistributionsTransformPCLGeneric::getHessian() c } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformPCLGeneric::getSearchMethodTarget() const { return ndt_ptr_->getSearchMethodTarget(); diff --git a/localization/ndt/include/ndt/impl/pcl_modified.hpp b/localization/ndt/include/ndt/impl/pcl_modified.hpp index 4715b85ffb4d4..f6c359fcb7158 100644 --- a/localization/ndt/include/ndt/impl/pcl_modified.hpp +++ b/localization/ndt/include/ndt/impl/pcl_modified.hpp @@ -35,14 +35,14 @@ void NormalDistributionsTransformPCLModified::align( template void NormalDistributionsTransformPCLModified::setInputTarget( - const boost::shared_ptr> & map_ptr) + const pcl::shared_ptr> & map_ptr) { ndt_ptr_->setInputTarget(map_ptr); } template void NormalDistributionsTransformPCLModified::setInputSource( - const boost::shared_ptr> & scan_ptr) + const pcl::shared_ptr> & scan_ptr) { ndt_ptr_->setInputSource(scan_ptr); } @@ -126,14 +126,14 @@ double NormalDistributionsTransformPCLModified::getFit } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformPCLModified::getInputTarget() const { return ndt_ptr_->getInputTarget(); } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformPCLModified::getInputSource() const { return ndt_ptr_->getInputSource(); @@ -162,7 +162,7 @@ NormalDistributionsTransformPCLModified::getHessian() } template -boost::shared_ptr> +pcl::shared_ptr> NormalDistributionsTransformPCLModified::getSearchMethodTarget() const { return ndt_ptr_->getSearchMethodTarget(); diff --git a/localization/ndt/include/ndt/omp.hpp b/localization/ndt/include/ndt/omp.hpp index 95c5f1bd4b2dc..9c323097cc8b6 100644 --- a/localization/ndt/include/ndt/omp.hpp +++ b/localization/ndt/include/ndt/omp.hpp @@ -17,7 +17,7 @@ #include "ndt/base.hpp" -#include +#include #include #include #include @@ -33,8 +33,8 @@ class NormalDistributionsTransformOMP ~NormalDistributionsTransformOMP() = default; void align(pcl::PointCloud & output, const Eigen::Matrix4f & guess) override; - void setInputTarget(const boost::shared_ptr> & map_ptr) override; - void setInputSource(const boost::shared_ptr> & scan_ptr) override; + void setInputTarget(const pcl::shared_ptr> & map_ptr) override; + void setInputSource(const pcl::shared_ptr> & scan_ptr) override; void setMaximumIterations(int max_iter) override; void setResolution(float res) override; @@ -49,15 +49,15 @@ class NormalDistributionsTransformOMP double getTransformationProbability() const override; double getNearestVoxelTransformationLikelihood() const override; double getFitnessScore() override; - boost::shared_ptr> getInputTarget() const override; - boost::shared_ptr> getInputSource() const override; + pcl::shared_ptr> getInputTarget() const override; + pcl::shared_ptr> getInputSource() const override; Eigen::Matrix4f getFinalTransformation() const override; std::vector> getFinalTransformationArray() const override; Eigen::Matrix getHessian() const override; - boost::shared_ptr> getSearchMethodTarget() const override; + pcl::shared_ptr> getSearchMethodTarget() const override; double calculateTransformationProbability( const pcl::PointCloud & trans_cloud) const override; @@ -72,7 +72,7 @@ class NormalDistributionsTransformOMP pclomp::NeighborSearchMethod getNeighborhoodSearchMethod() const; private: - boost::shared_ptr> ndt_ptr_; + pcl::shared_ptr> ndt_ptr_; }; #include "ndt/impl/omp.hpp" diff --git a/localization/ndt/include/ndt/pcl_generic.hpp b/localization/ndt/include/ndt/pcl_generic.hpp index 8ddb7dcc34006..63928510d54b2 100644 --- a/localization/ndt/include/ndt/pcl_generic.hpp +++ b/localization/ndt/include/ndt/pcl_generic.hpp @@ -17,7 +17,7 @@ #include "ndt/base.hpp" -#include +#include #include #include #include @@ -33,8 +33,8 @@ class NormalDistributionsTransformPCLGeneric ~NormalDistributionsTransformPCLGeneric() = default; void align(pcl::PointCloud & output, const Eigen::Matrix4f & guess) override; - void setInputTarget(const boost::shared_ptr> & map_ptr) override; - void setInputSource(const boost::shared_ptr> & scan_ptr) override; + void setInputTarget(const pcl::shared_ptr> & map_ptr) override; + void setInputSource(const pcl::shared_ptr> & scan_ptr) override; void setMaximumIterations(int max_iter) override; void setResolution(float res) override; @@ -49,15 +49,15 @@ class NormalDistributionsTransformPCLGeneric double getTransformationProbability() const override; double getNearestVoxelTransformationLikelihood() const override; double getFitnessScore() override; - boost::shared_ptr> getInputTarget() const override; - boost::shared_ptr> getInputSource() const override; + pcl::shared_ptr> getInputTarget() const override; + pcl::shared_ptr> getInputSource() const override; Eigen::Matrix4f getFinalTransformation() const override; std::vector> getFinalTransformationArray() const override; Eigen::Matrix getHessian() const override; - boost::shared_ptr> getSearchMethodTarget() const override; + pcl::shared_ptr> getSearchMethodTarget() const override; double calculateTransformationProbability( const pcl::PointCloud & trans_cloud) const override; @@ -65,7 +65,7 @@ class NormalDistributionsTransformPCLGeneric const pcl::PointCloud & trans_cloud) const override; private: - boost::shared_ptr> ndt_ptr_; + pcl::shared_ptr> ndt_ptr_; }; #include "ndt/impl/pcl_generic.hpp" diff --git a/localization/ndt/include/ndt/pcl_modified.hpp b/localization/ndt/include/ndt/pcl_modified.hpp index 34f50cd7553ba..df993566481e5 100644 --- a/localization/ndt/include/ndt/pcl_modified.hpp +++ b/localization/ndt/include/ndt/pcl_modified.hpp @@ -19,7 +19,7 @@ #include -#include +#include #include #include @@ -34,8 +34,8 @@ class NormalDistributionsTransformPCLModified ~NormalDistributionsTransformPCLModified() = default; void align(pcl::PointCloud & output, const Eigen::Matrix4f & guess) override; - void setInputTarget(const boost::shared_ptr> & map_ptr) override; - void setInputSource(const boost::shared_ptr> & scan_ptr) override; + void setInputTarget(const pcl::shared_ptr> & map_ptr) override; + void setInputSource(const pcl::shared_ptr> & scan_ptr) override; void setMaximumIterations(int max_iter) override; void setResolution(float res) override; @@ -50,15 +50,15 @@ class NormalDistributionsTransformPCLModified double getTransformationProbability() const override; double getNearestVoxelTransformationLikelihood() const override; double getFitnessScore() override; - boost::shared_ptr> getInputTarget() const override; - boost::shared_ptr> getInputSource() const override; + pcl::shared_ptr> getInputTarget() const override; + pcl::shared_ptr> getInputSource() const override; Eigen::Matrix4f getFinalTransformation() const override; std::vector> getFinalTransformationArray() const override; Eigen::Matrix getHessian() const override; - boost::shared_ptr> getSearchMethodTarget() const override; + pcl::shared_ptr> getSearchMethodTarget() const override; double calculateTransformationProbability( const pcl::PointCloud & trans_cloud) const override; @@ -66,7 +66,7 @@ class NormalDistributionsTransformPCLModified const pcl::PointCloud & trans_cloud) const override; private: - boost::shared_ptr> ndt_ptr_; + pcl::shared_ptr> ndt_ptr_; }; #include "ndt/impl/pcl_modified.hpp"