Skip to content

Commit

Permalink
Test hidden visibility default on gcc
Browse files Browse the repository at this point in the history
  • Loading branch information
mvieth committed Feb 27, 2024
1 parent 14a8bde commit 16e3e28
Show file tree
Hide file tree
Showing 17 changed files with 81 additions and 110 deletions.
6 changes: 6 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down Expand Up @@ -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()

Expand Down
4 changes: 4 additions & 0 deletions cmake/pcl_options.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -109,3 +109,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)
4 changes: 2 additions & 2 deletions common/include/pcl/common/intersections.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ namespace pcl
* \param[in] angular_tolerance tolerance in radians
* \return true if succeeded/planes aren't parallel
*/
PCL_EXPORTS template <typename Scalar> bool
template <typename Scalar> PCL_EXPORTS bool
planeWithPlaneIntersection (const Eigen::Matrix<Scalar, 4, 1> &plane_a,
const Eigen::Matrix<Scalar, 4, 1> &plane_b,
Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &line,
Expand Down Expand Up @@ -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 <typename Scalar> bool
template <typename Scalar> PCL_EXPORTS bool
threePlanesIntersection (const Eigen::Matrix<Scalar, 4, 1> &plane_a,
const Eigen::Matrix<Scalar, 4, 1> &plane_b,
const Eigen::Matrix<Scalar, 4, 1> &plane_c,
Expand Down
23 changes: 12 additions & 11 deletions common/include/pcl/exceptions.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include <stdexcept>
#include <sstream>
#include <boost/current_function.hpp>
#include <pcl/pcl_exports.h> // for PCL_EXPORTS

/** PCL_THROW_EXCEPTION a helper macro to be used for throwing exceptions.
* This is an example on how to use:
Expand All @@ -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:

Expand Down Expand Up @@ -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:

Expand All @@ -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:

Expand All @@ -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:

Expand All @@ -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:

Expand All @@ -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 = "",
Expand All @@ -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:

Expand All @@ -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:

Expand All @@ -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,
Expand All @@ -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,
Expand All @@ -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,
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/pcl_exports.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,5 +45,5 @@
#define PCL_EXPORTS
#endif
#else
#define PCL_EXPORTS
#define PCL_EXPORTS __attribute__ ((visibility ("default")))
#endif
2 changes: 1 addition & 1 deletion common/include/pcl/pcl_macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
12 changes: 0 additions & 12 deletions filters/src/convolution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,17 +189,5 @@ Convolution<pcl::RGB, pcl::RGB>::convolveOneColDense(int i, int j)
result.b = static_cast<std::uint8_t>(b);
return (result);
}

#ifndef PCL_NO_PRECOMPILE
#include <pcl/impl/instantiate.hpp>
#include <pcl/point_types.h>

PCL_INSTANTIATE_PRODUCT(
Convolution, ((pcl::RGB))((pcl::RGB)))

PCL_INSTANTIATE_PRODUCT(
Convolution, ((pcl::PointXYZRGB))((pcl::PointXYZRGB)))
#endif // PCL_NO_PRECOMPILE

} // namespace filters
} // namespace pcl
15 changes: 13 additions & 2 deletions filters/src/voxel_grid_label.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,19 @@
*/

#include <map>
#include <pcl/common/common.h> // for getMinMax3D
#include <pcl/filters/voxel_grid_label.h>
#include <pcl/filters/impl/voxel_grid.hpp>
#include <boost/mpl/size.hpp> // 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
Expand Down Expand Up @@ -111,7 +122,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)
int label_index = -1;
label_index = pcl::getFieldIndex<PointXYZRGBL> ("label", fields);

std::vector<cloud_point_index_idx> index_vector;
std::vector<point_index_idx> 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...
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ namespace registration {
* \ingroup registration
*/
template <typename PointSource, typename PointTarget, typename Scalar = float>
class TransformationEstimationSVD
class PCL_EXPORTS TransformationEstimationSVD
: public TransformationEstimation<PointSource, PointTarget, Scalar> {
public:
using Ptr = shared_ptr<TransformationEstimationSVD<PointSource, PointTarget, Scalar>>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ namespace pcl
* \ingroup sample_consensus
*/
template <typename PointT>
class SampleConsensusModelPlane : public SampleConsensusModel<PointT>
class PCL_EXPORTS SampleConsensusModelPlane : public SampleConsensusModel<PointT>
{
public:
using SampleConsensusModel<PointT>::model_name_;
Expand Down
7 changes: 7 additions & 0 deletions sample_consensus/src/sac_model_normal_plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,17 @@
#ifndef PCL_NO_PRECOMPILE
#include <pcl/impl/instantiate.hpp>
#include <pcl/point_types.h>

// 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<POINT_TYPE>;

// 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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,6 @@ pcl::CrfNormalSegmentation<PointT>::segmentPoints ()
{
}

#define PCL_INSTANTIATE_CrfNormalSegmentation(T) template class pcl::CrfNormalSegmentation<T>;
#define PCL_INSTANTIATE_CrfNormalSegmentation(T) template class PCL_EXPORTS pcl::CrfNormalSegmentation<T>;

#endif // PCL_CRF_NORMAL_SEGMENTATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -686,57 +686,11 @@ pcl::SupervoxelClustering<PointT>::getMaxLabel () const
return max_label;
}

namespace pcl
{
namespace octree
{
//Explicit overloads for RGB types
template<>
void
pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGB,pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData>::addPoint (const pcl::PointXYZRGB &new_point);

template<>
void
pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGBA,pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData>::addPoint (const pcl::PointXYZRGBA &new_point);

//Explicit overloads for RGB types
template<> void
pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGB,pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData>::computeData ();

template<> void
pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGBA,pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData>::computeData ();

//Explicit overloads for XYZ types
template<>
void
pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZ,pcl::SupervoxelClustering<pcl::PointXYZ>::VoxelData>::addPoint (const pcl::PointXYZ &new_point);

template<> void
pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZ,pcl::SupervoxelClustering<pcl::PointXYZ>::VoxelData>::computeData ();
}
}

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
namespace pcl
{

template<> void
pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData::getPoint (pcl::PointXYZRGB &point_arg) const;

template<> void
pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData::getPoint (pcl::PointXYZRGBA &point_arg ) const;

template<typename PointT> void
pcl::SupervoxelClustering<PointT>::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 <typename PointT> void
pcl::SupervoxelClustering<PointT>::VoxelData::getNormal (Normal &normal_arg) const
Expand Down
22 changes: 22 additions & 0 deletions segmentation/include/pcl/segmentation/supervoxel_clustering.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<typename PointT2 = PointT, traits::HasColor<PointT2> = true> void
getPoint (PointT &point_arg) const
{
point_arg.rgba = static_cast<std::uint32_t>(rgb_[0]) << 16 |
static_cast<std::uint32_t>(rgb_[1]) << 8 |
static_cast<std::uint32_t>(rgb_[2]);
point_arg.x = xyz_[0];
point_arg.y = xyz_[1];
point_arg.z = xyz_[2];
}

template<typename PointT2 = PointT, traits::HasNoColor<PointT2> = 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
Expand Down
Loading

0 comments on commit 16e3e28

Please sign in to comment.