diff --git a/CMakeLists.txt b/CMakeLists.txt index 92ffe0a4270..e8f03b2ecd3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -121,6 +121,9 @@ if(CMAKE_COMPILER_IS_GNUCXX) endif() string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra -fno-strict-aliasing ${SSE_FLAGS} ${AVX_FLAGS}") endif() + if(PCL_SYMBOL_VISIBILITY_HIDDEN) + string(APPEND CMAKE_CXX_FLAGS " -fvisibility=hidden -fvisibility-inlines-hidden") + endif() if(PCL_WARNINGS_ARE_ERRORS) string(APPEND CMAKE_CXX_FLAGS " -Werror -fno-strict-aliasing") @@ -229,6 +232,9 @@ if(CMAKE_COMPILER_IS_CLANG) string(APPEND CMAKE_CXX_FLAGS " -stdlib=libstdc++") endif() endif() + if(PCL_SYMBOL_VISIBILITY_HIDDEN) + string(APPEND CMAKE_CXX_FLAGS " -fvisibility=hidden -fvisibility-inlines-hidden") + endif() set(CLANG_LIBRARIES "stdc++") endif() diff --git a/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp b/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp index 6a88b8f46ea..740b927ac10 100644 --- a/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp +++ b/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp @@ -9,13 +9,13 @@ #include // Instantiation -template class pcl::rec_3d_framework:: +template class PCL_EXPORTS pcl::rec_3d_framework::GlobalClassifier; + +template class PCL_EXPORTS pcl::rec_3d_framework:: GlobalNNPipeline; -template class pcl::rec_3d_framework::GlobalNNPipeline< - Metrics::HistIntersectionUnionDistance, - pcl::PointXYZ, - pcl::VFHSignature308>; -template class pcl::rec_3d_framework:: +template class PCL_EXPORTS + pcl::rec_3d_framework::GlobalNNPipeline; +template class PCL_EXPORTS pcl::rec_3d_framework:: GlobalNNPipeline; - -template class pcl::rec_3d_framework::GlobalClassifier; diff --git a/cmake/pcl_options.cmake b/cmake/pcl_options.cmake index e4ca977857a..f1489aea83d 100644 --- a/cmake/pcl_options.cmake +++ b/cmake/pcl_options.cmake @@ -111,3 +111,7 @@ option(PCL_DISABLE_GPU_TESTS "Disable running GPU tests. If disabled, tests will # Set whether visualizations tests should be run # (Used to prevent visualizations tests from executing in CI where visualization is unavailable) option(PCL_DISABLE_VISUALIZATION_TESTS "Disable running visualizations tests. If disabled, tests will still be built." OFF) + +# This leads to smaller libraries, possibly faster code, and fixes some bugs. See https://gcc.gnu.org/wiki/Visibility +option(PCL_SYMBOL_VISIBILITY_HIDDEN "Hide all binary symbols by default, export only those explicitly marked (gcc and clang only). Experimental!" ON) +mark_as_advanced(PCL_SYMBOL_VISIBILITY_HIDDEN) diff --git a/common/include/pcl/common/intersections.h b/common/include/pcl/common/intersections.h index 28a3f80e828..3f4cd5ec2fc 100644 --- a/common/include/pcl/common/intersections.h +++ b/common/include/pcl/common/intersections.h @@ -86,7 +86,7 @@ namespace pcl * \param[in] angular_tolerance tolerance in radians * \return true if succeeded/planes aren't parallel */ - PCL_EXPORTS template bool + template PCL_EXPORTS bool planeWithPlaneIntersection (const Eigen::Matrix &plane_a, const Eigen::Matrix &plane_b, Eigen::Matrix &line, @@ -121,7 +121,7 @@ namespace pcl * \param[out] intersection_point the three coordinates x, y, z of the intersection point * \return true if succeeded/planes aren't parallel */ - PCL_EXPORTS template bool + template PCL_EXPORTS bool threePlanesIntersection (const Eigen::Matrix &plane_a, const Eigen::Matrix &plane_b, const Eigen::Matrix &plane_c, diff --git a/common/include/pcl/exceptions.h b/common/include/pcl/exceptions.h index 3814839c89c..975af1d2d88 100644 --- a/common/include/pcl/exceptions.h +++ b/common/include/pcl/exceptions.h @@ -40,6 +40,7 @@ #include #include #include +#include // for PCL_EXPORTS /** PCL_THROW_EXCEPTION a helper macro to be used for throwing exceptions. * This is an example on how to use: @@ -60,7 +61,7 @@ namespace pcl * \brief A base class for all pcl exceptions which inherits from std::runtime_error * \author Eitan Marder-Eppstein, Suat Gedikli, Nizar Sallem */ - class PCLException : public std::runtime_error + class PCL_EXPORTS PCLException : public std::runtime_error { public: @@ -132,7 +133,7 @@ namespace pcl /** \class InvalidConversionException * \brief An exception that is thrown when a PCLPointCloud2 message cannot be converted into a PCL type */ - class InvalidConversionException : public PCLException + class PCL_EXPORTS InvalidConversionException : public PCLException { public: @@ -146,7 +147,7 @@ namespace pcl /** \class IsNotDenseException * \brief An exception that is thrown when a PointCloud is not dense but is attempted to be used as dense */ - class IsNotDenseException : public PCLException + class PCL_EXPORTS IsNotDenseException : public PCLException { public: @@ -161,7 +162,7 @@ namespace pcl * \brief An exception that is thrown when a sample consensus model doesn't * have the correct number of samples defined in model_types.h */ - class InvalidSACModelTypeException : public PCLException + class PCL_EXPORTS InvalidSACModelTypeException : public PCLException { public: @@ -175,7 +176,7 @@ namespace pcl /** \class IOException * \brief An exception that is thrown during an IO error (typical read/write errors) */ - class IOException : public PCLException + class PCL_EXPORTS IOException : public PCLException { public: @@ -190,7 +191,7 @@ namespace pcl * \brief An exception thrown when init can not be performed should be used in all the * PCLBase class inheritants. */ - class InitFailedException : public PCLException + class PCL_EXPORTS InitFailedException : public PCLException { public: InitFailedException (const std::string& error_description = "", @@ -204,7 +205,7 @@ namespace pcl * \brief An exception that is thrown when an organized point cloud is needed * but not provided. */ - class UnorganizedPointCloudException : public PCLException + class PCL_EXPORTS UnorganizedPointCloudException : public PCLException { public: @@ -218,7 +219,7 @@ namespace pcl /** \class KernelWidthTooSmallException * \brief An exception that is thrown when the kernel size is too small */ - class KernelWidthTooSmallException : public PCLException + class PCL_EXPORTS KernelWidthTooSmallException : public PCLException { public: @@ -229,7 +230,7 @@ namespace pcl : pcl::PCLException (error_description, file_name, function_name, line_number) { } } ; - class UnhandledPointTypeException : public PCLException + class PCL_EXPORTS UnhandledPointTypeException : public PCLException { public: UnhandledPointTypeException (const std::string& error_description, @@ -239,7 +240,7 @@ namespace pcl : pcl::PCLException (error_description, file_name, function_name, line_number) { } }; - class ComputeFailedException : public PCLException + class PCL_EXPORTS ComputeFailedException : public PCLException { public: ComputeFailedException (const std::string& error_description, @@ -252,7 +253,7 @@ namespace pcl /** \class BadArgumentException * \brief An exception that is thrown when the arguments number or type is wrong/unhandled. */ - class BadArgumentException : public PCLException + class PCL_EXPORTS BadArgumentException : public PCLException { public: BadArgumentException (const std::string& error_description, diff --git a/common/include/pcl/pcl_exports.h b/common/include/pcl/pcl_exports.h index ef71bddadd8..8676382c1c5 100644 --- a/common/include/pcl/pcl_exports.h +++ b/common/include/pcl/pcl_exports.h @@ -45,5 +45,5 @@ #define PCL_EXPORTS #endif #else - #define PCL_EXPORTS + #define PCL_EXPORTS __attribute__ ((visibility ("default"))) #endif diff --git a/common/include/pcl/pcl_macros.h b/common/include/pcl/pcl_macros.h index da487b5e1bc..a8e19d05116 100644 --- a/common/include/pcl/pcl_macros.h +++ b/common/include/pcl/pcl_macros.h @@ -323,7 +323,7 @@ pcl_round (float number) #define PCL_EXPORTS #endif #else - #define PCL_EXPORTS + #define PCL_EXPORTS __attribute__ ((visibility ("default"))) #endif #if defined WIN32 || defined _WIN32 diff --git a/features/include/pcl/features/moment_of_inertia_estimation.h b/features/include/pcl/features/moment_of_inertia_estimation.h index 9d96d407157..9fa7669d6db 100644 --- a/features/include/pcl/features/moment_of_inertia_estimation.h +++ b/features/include/pcl/features/moment_of_inertia_estimation.h @@ -352,7 +352,7 @@ namespace pcl }; } -#define PCL_INSTANTIATE_MomentOfInertiaEstimation(T) template class pcl::MomentOfInertiaEstimation; +#define PCL_INSTANTIATE_MomentOfInertiaEstimation(T) template class PCL_EXPORTS pcl::MomentOfInertiaEstimation; #ifdef PCL_NO_PRECOMPILE #include diff --git a/features/include/pcl/features/rops_estimation.h b/features/include/pcl/features/rops_estimation.h index a34e09fc941..b46c504c59e 100644 --- a/features/include/pcl/features/rops_estimation.h +++ b/features/include/pcl/features/rops_estimation.h @@ -227,7 +227,7 @@ namespace pcl }; } -#define PCL_INSTANTIATE_ROPSEstimation(InT, OutT) template class pcl::ROPSEstimation; +#define PCL_INSTANTIATE_ROPSEstimation(InT, OutT) template class PCL_EXPORTS pcl::ROPSEstimation; #ifdef PCL_NO_PRECOMPILE #include diff --git a/filters/src/convolution.cpp b/filters/src/convolution.cpp index 7d35a463a0c..41ffd02be9c 100644 --- a/filters/src/convolution.cpp +++ b/filters/src/convolution.cpp @@ -189,17 +189,5 @@ Convolution::convolveOneColDense(int i, int j) result.b = static_cast(b); return (result); } - -#ifndef PCL_NO_PRECOMPILE -#include -#include - -PCL_INSTANTIATE_PRODUCT( - Convolution, ((pcl::RGB))((pcl::RGB))) - -PCL_INSTANTIATE_PRODUCT( - Convolution, ((pcl::PointXYZRGB))((pcl::PointXYZRGB))) -#endif // PCL_NO_PRECOMPILE - } // namespace filters } // namespace pcl diff --git a/filters/src/voxel_grid_label.cpp b/filters/src/voxel_grid_label.cpp index 13dd7cdfdb4..12831d2b0b6 100644 --- a/filters/src/voxel_grid_label.cpp +++ b/filters/src/voxel_grid_label.cpp @@ -37,8 +37,19 @@ */ #include +#include // for getMinMax3D #include -#include +#include // for boost::mpl::size + +struct point_index_idx +{ + unsigned int idx; + unsigned int cloud_point_index; + + point_index_idx() = default; + point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {} + bool operator < (const point_index_idx &p) const { return (idx < p.idx); } +}; ////////////////////////////////////////////////////////////////////////////// void @@ -111,7 +122,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output) int label_index = -1; label_index = pcl::getFieldIndex ("label", fields); - std::vector index_vector; + std::vector index_vector; index_vector.reserve(input_->size()); // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first... diff --git a/recognition/src/implicit_shape_model.cpp b/recognition/src/implicit_shape_model.cpp index ed851c35009..9efa48f4cb8 100644 --- a/recognition/src/implicit_shape_model.cpp +++ b/recognition/src/implicit_shape_model.cpp @@ -43,6 +43,6 @@ #include // Instantiations of specific point types -template class pcl::features::ISMVoteList; +template class PCL_EXPORTS pcl::features::ISMVoteList; -template class pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>; +template class PCL_EXPORTS pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>; diff --git a/registration/include/pcl/registration/transformation_estimation_svd.h b/registration/include/pcl/registration/transformation_estimation_svd.h index d91f7e367a0..77b0646679f 100644 --- a/registration/include/pcl/registration/transformation_estimation_svd.h +++ b/registration/include/pcl/registration/transformation_estimation_svd.h @@ -54,7 +54,7 @@ namespace registration { * \ingroup registration */ template -class TransformationEstimationSVD +class PCL_EXPORTS TransformationEstimationSVD : public TransformationEstimation { public: using Ptr = shared_ptr>; diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h index 6137c26126c..e1e1e60bddf 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h @@ -45,7 +45,7 @@ namespace pcl { namespace internal { - int optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + PCL_EXPORTS int optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); } // namespace internal /** \brief @b SampleConsensusModelCone defines a model for 3D cone segmentation. diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h index 95a6e80873b..a3113a6f35f 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h @@ -47,7 +47,7 @@ namespace pcl { namespace internal { - int optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + PCL_EXPORTS int optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); } // namespace internal /** \brief @b SampleConsensusModelCylinder defines a model for 3D cylinder segmentation. diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h b/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h index 2bee660a23f..a82e8e5771e 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h @@ -139,7 +139,7 @@ namespace pcl * \ingroup sample_consensus */ template - class SampleConsensusModelPlane : public SampleConsensusModel + class PCL_EXPORTS SampleConsensusModelPlane : public SampleConsensusModel { public: using SampleConsensusModel::model_name_; diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h index 537fcb3d0dd..7645c636545 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h @@ -53,7 +53,7 @@ namespace pcl { namespace internal { - int optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + PCL_EXPORTS int optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); } // namespace internal /** \brief SampleConsensusModelSphere defines a model for 3D sphere segmentation. diff --git a/sample_consensus/src/sac_model_normal_plane.cpp b/sample_consensus/src/sac_model_normal_plane.cpp index d7b2aec34e4..0a2c08dadbd 100644 --- a/sample_consensus/src/sac_model_normal_plane.cpp +++ b/sample_consensus/src/sac_model_normal_plane.cpp @@ -41,10 +41,17 @@ #ifndef PCL_NO_PRECOMPILE #include #include + +// used to tell compiler that instantiations of SampleConsensusModelPlane are available from sac_model_plane.cpp +#define PCL_EXTERN_TEMPLATE_IMPL(r, unused, POINT_TYPE) \ + extern template class pcl::SampleConsensusModelPlane; + // Instantiations of specific point types #ifdef PCL_ONLY_CORE_POINT_TYPES + BOOST_PP_SEQ_FOR_EACH(PCL_EXTERN_TEMPLATE_IMPL, unused, (pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGBA)(pcl::PointXYZRGB)(pcl::PointXYZRGBNormal)) PCL_INSTANTIATE_PRODUCT(SampleConsensusModelNormalPlane, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGBA)(pcl::PointXYZRGB))((pcl::Normal))) #else + BOOST_PP_SEQ_FOR_EACH(PCL_EXTERN_TEMPLATE_IMPL, unused, PCL_XYZ_POINT_TYPES) PCL_INSTANTIATE_PRODUCT(SampleConsensusModelNormalPlane, (PCL_XYZ_POINT_TYPES)(PCL_NORMAL_POINT_TYPES)) #endif #endif // PCL_NO_PRECOMPILE diff --git a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp index 4a98b2e33bf..9481fc42a14 100644 --- a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp @@ -276,7 +276,7 @@ pcl::ApproximateProgressiveMorphologicalFilter::extract (Indices& ground } -#define PCL_INSTANTIATE_ApproximateProgressiveMorphologicalFilter(T) template class pcl::ApproximateProgressiveMorphologicalFilter; +#define PCL_INSTANTIATE_ApproximateProgressiveMorphologicalFilter(T) template class PCL_EXPORTS pcl::ApproximateProgressiveMorphologicalFilter; #endif // PCL_SEGMENTATION_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/crf_normal_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/crf_normal_segmentation.hpp index cf00fa56a84..01b9dba9a91 100644 --- a/segmentation/include/pcl/segmentation/impl/crf_normal_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/crf_normal_segmentation.hpp @@ -71,6 +71,6 @@ pcl::CrfNormalSegmentation::segmentPoints () { } -#define PCL_INSTANTIATE_CrfNormalSegmentation(T) template class pcl::CrfNormalSegmentation; +#define PCL_INSTANTIATE_CrfNormalSegmentation(T) template class PCL_EXPORTS pcl::CrfNormalSegmentation; #endif // PCL_CRF_NORMAL_SEGMENTATION_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp index 2c2f9f5bac0..ff061567519 100644 --- a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp @@ -595,6 +595,6 @@ pcl::CrfSegmentation::segmentPoints (pcl::PointCloud } -#define PCL_INSTANTIATE_CrfSegmentation(T) template class pcl::CrfSegmentation; +#define PCL_INSTANTIATE_CrfSegmentation(T) template class PCL_EXPORTS pcl::CrfSegmentation; #endif // PCL_CRF_SEGMENTATION_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp index 0288a260497..e97e457e8ad 100644 --- a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp @@ -598,6 +598,6 @@ pcl::MinCutSegmentation::getColoredCloud () return (colored_cloud); } -#define PCL_INSTANTIATE_MinCutSegmentation(T) template class pcl::MinCutSegmentation; +#define PCL_INSTANTIATE_MinCutSegmentation(T) template class PCL_EXPORTS pcl::MinCutSegmentation; #endif // PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp index 1c1ee2e0148..d676dffe6c9 100644 --- a/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp @@ -143,7 +143,7 @@ pcl::ProgressiveMorphologicalFilter::extract (Indices& ground) deinitCompute (); } -#define PCL_INSTANTIATE_ProgressiveMorphologicalFilter(T) template class pcl::ProgressiveMorphologicalFilter; +#define PCL_INSTANTIATE_ProgressiveMorphologicalFilter(T) template class PCL_EXPORTS pcl::ProgressiveMorphologicalFilter; #endif // PCL_SEGMENTATION_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index be75d0cf7ba..a91a02dee07 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -724,5 +724,5 @@ pcl::RegionGrowing::getColoredCloudRGBA () return (colored_cloud); } -#define PCL_INSTANTIATE_RegionGrowing(T) template class pcl::RegionGrowing; +#define PCL_INSTANTIATE_RegionGrowing(T) template class PCL_EXPORTS pcl::RegionGrowing; diff --git a/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp index 54aed117bbe..44dcee2b388 100644 --- a/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp +++ b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp @@ -689,57 +689,11 @@ pcl::SupervoxelClustering::getMaxLabel () const return max_label; } -namespace pcl -{ - namespace octree - { - //Explicit overloads for RGB types - template<> - void - pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::addPoint (const pcl::PointXYZRGB &new_point); - - template<> - void - pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::addPoint (const pcl::PointXYZRGBA &new_point); - - //Explicit overloads for RGB types - template<> void - pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::computeData (); - - template<> void - pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::computeData (); - - //Explicit overloads for XYZ types - template<> - void - pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::addPoint (const pcl::PointXYZ &new_point); - - template<> void - pcl::octree::OctreePointCloudAdjacencyContainer::VoxelData>::computeData (); - } -} - ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// namespace pcl -{ - - template<> void - pcl::SupervoxelClustering::VoxelData::getPoint (pcl::PointXYZRGB &point_arg) const; - - template<> void - pcl::SupervoxelClustering::VoxelData::getPoint (pcl::PointXYZRGBA &point_arg ) const; - - template void - pcl::SupervoxelClustering::VoxelData::getPoint (PointT &point_arg ) const - { - //XYZ is required or this doesn't make much sense... - point_arg.x = xyz_[0]; - point_arg.y = xyz_[1]; - point_arg.z = xyz_[2]; - } - +{ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::SupervoxelClustering::VoxelData::getNormal (Normal &normal_arg) const diff --git a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp index 38f2cd59cda..4d59eddfc82 100644 --- a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp +++ b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp @@ -427,6 +427,6 @@ pcl::UnaryClassifier::segment (pcl::PointCloud::Ptr & } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -#define PCL_INSTANTIATE_UnaryClassifier(T) template class pcl::UnaryClassifier; +#define PCL_INSTANTIATE_UnaryClassifier(T) template class PCL_EXPORTS pcl::UnaryClassifier; #endif // PCL_UNARY_CLASSIFIER_HPP_ diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index e46239c50af..31dcb4be480 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -145,11 +145,33 @@ namespace pcl owner_ (nullptr) {} +#ifdef DOXYGEN_ONLY /** \brief Gets the data of in the form of a point * \param[out] point_arg Will contain the point value of the voxeldata */ void getPoint (PointT &point_arg) const; +#else + template = true> void + getPoint (PointT &point_arg) const + { + point_arg.rgba = static_cast(rgb_[0]) << 16 | + static_cast(rgb_[1]) << 8 | + static_cast(rgb_[2]); + point_arg.x = xyz_[0]; + point_arg.y = xyz_[1]; + point_arg.z = xyz_[2]; + } + + template = true> void + getPoint (PointT &point_arg ) const + { + //XYZ is required or this doesn't make much sense... + point_arg.x = xyz_[0]; + point_arg.y = xyz_[1]; + point_arg.z = xyz_[2]; + } +#endif /** \brief Gets the data of in the form of a normal * \param[out] normal_arg Will contain the normal value of the voxeldata diff --git a/segmentation/src/crf_segmentation.cpp b/segmentation/src/crf_segmentation.cpp index cb06b73b75f..fffdcccb5f6 100644 --- a/segmentation/src/crf_segmentation.cpp +++ b/segmentation/src/crf_segmentation.cpp @@ -43,6 +43,6 @@ #include // Instantiations of specific point types -template class pcl::CrfSegmentation; -template class pcl::CrfSegmentation; -template class pcl::CrfSegmentation; +template class PCL_EXPORTS pcl::CrfSegmentation; +template class PCL_EXPORTS pcl::CrfSegmentation; +template class PCL_EXPORTS pcl::CrfSegmentation; diff --git a/segmentation/src/region_growing_rgb.cpp b/segmentation/src/region_growing_rgb.cpp index 76b724e1cae..f377ca0e983 100644 --- a/segmentation/src/region_growing_rgb.cpp +++ b/segmentation/src/region_growing_rgb.cpp @@ -43,7 +43,7 @@ #include // Instantiations of specific point types -template class pcl::RegionGrowingRGB; -template class pcl::RegionGrowingRGB; -template class pcl::RegionGrowingRGB; -template class pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; diff --git a/segmentation/src/supervoxel_clustering.cpp b/segmentation/src/supervoxel_clustering.cpp index 663b0eda7c1..821901ec540 100644 --- a/segmentation/src/supervoxel_clustering.cpp +++ b/segmentation/src/supervoxel_clustering.cpp @@ -49,6 +49,10 @@ #include #include +template class PCL_EXPORTS pcl::SupervoxelClustering; +template class PCL_EXPORTS pcl::SupervoxelClustering; +template class PCL_EXPORTS pcl::SupervoxelClustering; + namespace pcl { namespace octree @@ -135,31 +139,6 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -namespace pcl -{ - template<> void - pcl::SupervoxelClustering::VoxelData::getPoint (pcl::PointXYZRGB &point_arg) const - { - point_arg.rgba = static_cast(rgb_[0]) << 16 | - static_cast(rgb_[1]) << 8 | - static_cast(rgb_[2]); - point_arg.x = xyz_[0]; - point_arg.y = xyz_[1]; - point_arg.z = xyz_[2]; - } - - template<> void - pcl::SupervoxelClustering::VoxelData::getPoint (pcl::PointXYZRGBA &point_arg ) const - { - point_arg.rgba = static_cast(rgb_[0]) << 16 | - static_cast(rgb_[1]) << 8 | - static_cast(rgb_[2]); - point_arg.x = xyz_[0]; - point_arg.y = xyz_[1]; - point_arg.z = xyz_[2]; - } -} - using VoxelDataT = pcl::SupervoxelClustering::VoxelData; using VoxelDataRGBT = pcl::SupervoxelClustering::VoxelData; using VoxelDataRGBAT = pcl::SupervoxelClustering::VoxelData; @@ -168,10 +147,6 @@ using AdjacencyContainerT = pcl::octree::OctreePointCloudAdjacencyContainer; using AdjacencyContainerRGBAT = pcl::octree::OctreePointCloudAdjacencyContainer; -template class pcl::SupervoxelClustering; -template class pcl::SupervoxelClustering; -template class pcl::SupervoxelClustering; - template class pcl::octree::OctreePointCloudAdjacencyContainer; template class pcl::octree::OctreePointCloudAdjacencyContainer; template class pcl::octree::OctreePointCloudAdjacencyContainer; diff --git a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h index 8e54f38e8f8..3190f9c1098 100644 --- a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h +++ b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h @@ -11,7 +11,8 @@ namespace tracking { * \ingroup tracking */ template -class NearestPairPointCloudCoherence : public PointCloudCoherence { +class PCL_EXPORTS NearestPairPointCloudCoherence +: public PointCloudCoherence { public: using PointCloudCoherence::getClassName; using PointCloudCoherence::coherence_name_; diff --git a/tracking/src/coherence.cpp b/tracking/src/coherence.cpp index 325e03aee83..5af35475c67 100644 --- a/tracking/src/coherence.cpp +++ b/tracking/src/coherence.cpp @@ -45,13 +45,13 @@ #include // clang-format off -PCL_INSTANTIATE(ApproxNearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES) PCL_INSTANTIATE(DistanceCoherence, PCL_XYZ_POINT_TYPES) PCL_INSTANTIATE(HSVColorCoherence, (pcl::PointXYZRGB) (pcl::PointXYZRGBNormal) (pcl::PointXYZRGBA)) PCL_INSTANTIATE(NearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES) +PCL_INSTANTIATE(ApproxNearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES) // TODO necessary to use this order? PCL_INSTANTIATE(NormalCoherence, PCL_NORMAL_POINT_TYPES) // clang-format on #endif // PCL_NO_PRECOMPILE diff --git a/visualization/include/pcl/visualization/common/ren_win_interact_map.h b/visualization/include/pcl/visualization/common/ren_win_interact_map.h index 1841f13a28f..31810c5fd83 100644 --- a/visualization/include/pcl/visualization/common/ren_win_interact_map.h +++ b/visualization/include/pcl/visualization/common/ren_win_interact_map.h @@ -38,6 +38,8 @@ #pragma once +#include + #include #include @@ -53,7 +55,7 @@ namespace pcl { namespace visualization { - class RenWinInteract + class PCL_EXPORTS RenWinInteract { public: