From 79cc27b28e8e42a836f849c1b93c6c0c2870cbdf Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 2 Aug 2023 11:47:19 +0200 Subject: [PATCH] Test hidden visibility default on gcc --- CMakeLists.txt | 6 +++ cmake/pcl_options.cmake | 4 ++ common/include/pcl/common/intersections.h | 4 +- common/include/pcl/exceptions.h | 23 ++++---- common/include/pcl/pcl_exports.h | 2 +- common/include/pcl/pcl_macros.h | 2 +- common/include/pcl/range_image/range_image.h | 54 +++++++++---------- filters/src/convolution.cpp | 12 ----- filters/src/voxel_grid_label.cpp | 15 +++++- .../transformation_estimation_svd.h | 2 +- .../impl/sac_model_normal_plane.hpp | 1 - .../pcl/sample_consensus/sac_model_plane.h | 6 +-- .../impl/crf_normal_segmentation.hpp | 2 +- .../impl/supervoxel_clustering.hpp | 48 +---------------- .../pcl/segmentation/supervoxel_clustering.h | 22 ++++++++ segmentation/src/supervoxel_clustering.cpp | 33 ++---------- .../nearest_pair_point_cloud_coherence.h | 3 +- .../common/ren_win_interact_map.h | 4 +- 18 files changed, 103 insertions(+), 140 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1741d73e20e..c55ee260a5a 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/cmake/pcl_options.cmake b/cmake/pcl_options.cmake index 1911fdf8a82..9f069ad8008 100644 --- a/cmake/pcl_options.cmake +++ b/cmake/pcl_options.cmake @@ -112,3 +112,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 ff227ab4382..81b578e57f6 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 3c1a3d1838c..5adfccf7585 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: @@ -62,7 +63,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: @@ -134,7 +135,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: @@ -148,7 +149,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: @@ -163,7 +164,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: @@ -177,7 +178,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: @@ -192,7 +193,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 = "", @@ -206,7 +207,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: @@ -220,7 +221,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: @@ -231,7 +232,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, @@ -241,7 +242,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, @@ -254,7 +255,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 074b11149ed..dcd2ce02587 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/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index 051979fe91f..fa2d5a74736 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -51,7 +51,7 @@ namespace pcl * \author Bastian Steder * \ingroup range_image */ - class RangeImage : public pcl::PointCloud + class PCL_EXPORTS RangeImage : public pcl::PointCloud { public: // =====TYPEDEFS===== @@ -69,9 +69,9 @@ namespace pcl // =====CONSTRUCTOR & DESTRUCTOR===== /** Constructor */ - PCL_EXPORTS RangeImage (); + RangeImage (); /** Destructor */ - PCL_EXPORTS virtual ~RangeImage () = default; + virtual ~RangeImage () = default; // =====STATIC VARIABLES===== /** The maximum number of openmp threads that can be used in this class */ @@ -99,7 +99,7 @@ namespace pcl * \param coordinate_frame the input coordinate frame * \param transformation the resulting transformation that warps \a coordinate_frame into CAMERA_FRAME */ - PCL_EXPORTS static void + static void getCoordinateFrameTransformation (RangeImage::CoordinateFrame coordinate_frame, Eigen::Affine3f& transformation); @@ -115,7 +115,7 @@ namespace pcl * \param point_cloud_data a PCLPointCloud2 message containing the input cloud * \param far_ranges the resulting cloud containing those points with far ranges */ - PCL_EXPORTS static void + static void extractFarRanges (const pcl::PCLPointCloud2& point_cloud_data, PointCloud& far_ranges); // =====METHODS===== @@ -124,7 +124,7 @@ namespace pcl makeShared () { return Ptr (new RangeImage (*this)); } /** \brief Reset all values to an empty range image */ - PCL_EXPORTS void + void reset (); /** \brief Create the depth image from a point cloud @@ -321,14 +321,14 @@ namespace pcl * \param bottom if positive, this value overrides the position of the bottom edge (defaults to -1) * \param left if positive, this value overrides the position of the left edge (defaults to -1) */ - PCL_EXPORTS void + void cropImage (int border_size=0, int top=-1, int right=-1, int bottom=-1, int left=-1); /** \brief Get all the range values in one float array of size width*height * \return a pointer to a new float array containing the range values * \note This method allocates a new float array; the caller is responsible for freeing this memory. */ - PCL_EXPORTS float* + float* getRangesArray () const; /** Getter for the transformation from the world system into the range image system @@ -445,7 +445,7 @@ namespace pcl calculate3DPoint (float image_x, float image_y, Eigen::Vector3f& point) const; /** Recalculate all 3D point positions according to their pixel position and range */ - PCL_EXPORTS void + void recalculate3DPointPositions (); /** Get imagePoint from 3D point in world coordinates */ @@ -568,7 +568,7 @@ namespace pcl inline float getImpactAngleBasedOnLocalNormal (int x, int y, int radius) const; /** Uses the above function for every point in the image */ - PCL_EXPORTS float* + float* getImpactAngleImageBasedOnLocalNormals (int radius) const; /** Calculate a score [0,1] that tells how acute the impact angle is (1.0f - getImpactAngle/90deg) @@ -586,7 +586,7 @@ namespace pcl getAcutenessValue (int x1, int y1, int x2, int y2) const; /** Calculate getAcutenessValue for every point */ - PCL_EXPORTS void + void getAcutenessValueImages (int pixel_distance, float*& acuteness_value_image_x, float*& acuteness_value_image_y) const; @@ -597,11 +597,11 @@ namespace pcl // const PointWithRange& neighbor2) const; /** Calculates, how much the surface changes at a point. 1 meaning a 90deg angle and 0 a flat surface */ - PCL_EXPORTS float + float getSurfaceChange (int x, int y, int radius) const; /** Uses the above function for every point in the image */ - PCL_EXPORTS float* + float* getSurfaceChangeImage (int radius) const; /** Calculates, how much the surface changes at a point. Returns an angle [0.0f, PI] for x and y direction. @@ -610,7 +610,7 @@ namespace pcl getSurfaceAngleChange (int x, int y, int radius, float& angle_change_x, float& angle_change_y) const; /** Uses the above function for every point in the image */ - PCL_EXPORTS void + void getSurfaceAngleChangeImages (int radius, float*& angle_change_image_x, float*& angle_change_image_y) const; /** Calculates the curvature in a point using pca */ @@ -622,7 +622,7 @@ namespace pcl getSensorPos () const; /** Sets all -INFINITY values to INFINITY */ - PCL_EXPORTS void + void setUnseenToMaxRange (); //! Getter for image_offset_x_ @@ -660,22 +660,22 @@ namespace pcl getHalfImage (RangeImage& half_image) const; //! Find the minimum and maximum range in the image - PCL_EXPORTS void + void getMinMaxRanges (float& min_range, float& max_range) const; //! This function sets the sensor pose to 0 and transforms all point positions to this local coordinate frame - PCL_EXPORTS void + void change3dPointsToLocalCoordinateFrame (); /** Calculate a range patch as the z values of the coordinate frame given by pose. * The patch will have size pixel_size x pixel_size and each pixel * covers world_size/pixel_size meters in the world * You are responsible for deleting the structure afterwards! */ - PCL_EXPORTS float* + float* getInterpolatedSurfaceProjection (const Eigen::Affine3f& pose, int pixel_size, float world_size) const; //! Same as above, but using the local coordinate frame defined by point and the viewing direction - PCL_EXPORTS float* + float* getInterpolatedSurfaceProjection (const Eigen::Vector3f& point, int pixel_size, float world_size) const; //! Get the local coordinate frame with 0,0,0 in point, upright and Z as the viewing direction @@ -690,22 +690,22 @@ namespace pcl getRotationToViewerCoordinateFrame (const Eigen::Vector3f& point, Eigen::Affine3f& transformation) const; /** Get a local coordinate frame at the given point based on the normal. */ - PCL_EXPORTS bool + bool getNormalBasedUprightTransformation (const Eigen::Vector3f& point, float max_dist, Eigen::Affine3f& transformation) const; /** Get the integral image of the range values (used for fast blur operations). * You are responsible for deleting it after usage! */ - PCL_EXPORTS void + void getIntegralImage (float*& integral_image, int*& valid_points_num_image) const; /** Get a blurred version of the range image using box filters on the provided integral image*/ - PCL_EXPORTS void // Template necessary so that this function also works in derived classes + void // Template necessary so that this function also works in derived classes getBlurredImageUsingIntegralImage (int blur_radius, float* integral_image, int* valid_points_num_image, RangeImage& range_image) const; /** Get a blurred version of the range image using box filters */ - PCL_EXPORTS virtual void // Template necessary so that this function also works in derived classes + virtual void // Template necessary so that this function also works in derived classes getBlurredImage (int blur_radius, RangeImage& range_image) const; /** Get the squared euclidean distance between the two image points. @@ -717,7 +717,7 @@ namespace pcl getAverageEuclideanDistance (int x, int y, int offset_x, int offset_y, int max_steps) const; //! Project all points on the local plane approximation, thereby smoothing the surface of the scan - PCL_EXPORTS void + void getRangeImageWithSmoothedSurface (int radius, RangeImage& smoothed_range_image) const; //void getLocalNormals (int radius) const; @@ -731,7 +731,7 @@ namespace pcl /** Calculates the overlap of two range images given the relative transformation * (from the given image to *this) */ - PCL_EXPORTS float + float getOverlap (const RangeImage& other_range_image, const Eigen::Affine3f& relative_transformation, int search_radius, float max_distance, int pixel_step=1) const; @@ -745,11 +745,11 @@ namespace pcl /** Return a newly created Range image. * Can be reimplemented in derived classes like RangeImagePlanar to return an image of the same type. */ - PCL_EXPORTS virtual RangeImage* + virtual RangeImage* getNew () const { return new RangeImage; } /** Copy other to *this. Necessary for use in virtual functions that need to copy derived RangeImage classes (like RangeImagePlanar) */ - PCL_EXPORTS virtual void + virtual void copyTo (RangeImage& other) const; 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/registration/include/pcl/registration/transformation_estimation_svd.h b/registration/include/pcl/registration/transformation_estimation_svd.h index f9c56ea59a2..60c960788bd 100644 --- a/registration/include/pcl/registration/transformation_estimation_svd.h +++ b/registration/include/pcl/registration/transformation_estimation_svd.h @@ -55,7 +55,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/impl/sac_model_normal_plane.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp index 0cd94ff80ee..dc96852c247 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp @@ -42,7 +42,6 @@ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PLANE_H_ #include -#include // for dist4, dist8 #include // for getAngle3D ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// 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..dcf1d095a5a 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_; @@ -293,11 +293,11 @@ namespace pcl #endif #ifdef __AVX__ - inline __m256 dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const; + __m256 dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const; #endif #ifdef __SSE__ - inline __m128 dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const; + __m128 dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const; #endif private: 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/supervoxel_clustering.hpp b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp index 9d627c600ff..81e18855189 100644 --- a/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp +++ b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp @@ -686,57 +686,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/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index e9e8018bf55..4c6a4b76a6e 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -143,11 +143,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/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 f7d6eda2a2b..e096baaab60 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/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: