Skip to content

Commit d5c1a97

Browse files
committed
Preparation for hidden visibility on gcc
In voxel_grid_label.cpp, the implementation of `VoxelGrid` (from voxel_grid.hpp) must not be available, otherwise `VoxelGrid` is instantiated again, but with the wrong visibility attributes (would overwrite the correct instantiation from `voxel_grid.cpp`). Same thing in sac_model_normal_plane.hpp: the implementation of `SampleConsensusModelPlane` must not be available. The implementations of `dist8` and `dist4` are moved from sac_model_plane.hpp to sac_model_plane.h so that they are available when `SampleConsensusModelNormalPlane` is instantiated and the compiler can optimize.
1 parent b0b2519 commit d5c1a97

File tree

11 files changed

+57
-57
lines changed

11 files changed

+57
-57
lines changed

common/include/pcl/common/intersections.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ namespace pcl
8686
* \param[in] angular_tolerance tolerance in radians
8787
* \return true if succeeded/planes aren't parallel
8888
*/
89-
PCL_EXPORTS template <typename Scalar> bool
89+
template <typename Scalar> PCL_EXPORTS bool
9090
planeWithPlaneIntersection (const Eigen::Matrix<Scalar, 4, 1> &plane_a,
9191
const Eigen::Matrix<Scalar, 4, 1> &plane_b,
9292
Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &line,
@@ -121,7 +121,7 @@ namespace pcl
121121
* \param[out] intersection_point the three coordinates x, y, z of the intersection point
122122
* \return true if succeeded/planes aren't parallel
123123
*/
124-
PCL_EXPORTS template <typename Scalar> bool
124+
template <typename Scalar> PCL_EXPORTS bool
125125
threePlanesIntersection (const Eigen::Matrix<Scalar, 4, 1> &plane_a,
126126
const Eigen::Matrix<Scalar, 4, 1> &plane_b,
127127
const Eigen::Matrix<Scalar, 4, 1> &plane_c,

filters/include/pcl/filters/impl/voxel_grid.hpp

Lines changed: 2 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -211,16 +211,6 @@ pcl::getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
211211
max_pt = max_p;
212212
}
213213

214-
struct cloud_point_index_idx
215-
{
216-
unsigned int idx;
217-
unsigned int cloud_point_index;
218-
219-
cloud_point_index_idx() = default;
220-
cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {}
221-
bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); }
222-
};
223-
224214
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
225215
template <typename PointT> void
226216
pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
@@ -273,7 +263,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
273263
divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
274264

275265
// Storage for mapping leaf and pointcloud indexes
276-
std::vector<cloud_point_index_idx> index_vector;
266+
std::vector<internal::cloud_point_index_idx> index_vector;
277267
index_vector.reserve (indices_->size ());
278268

279269
// If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
@@ -350,7 +340,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
350340

351341
// Second pass: sort the index_vector vector using value representing target cell as index
352342
// in effect all points belonging to the same output cell will be next to each other
353-
auto rightshift_func = [](const cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
343+
auto rightshift_func = [](const internal::cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
354344
boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func);
355345

356346
// Third pass: count output cells

filters/include/pcl/filters/voxel_grid.h

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -866,6 +866,21 @@ namespace pcl
866866
void
867867
applyFilter (PCLPointCloud2 &output) override;
868868
};
869+
870+
namespace internal
871+
{
872+
/** \brief Used internally in voxel grid classes.
873+
*/
874+
struct cloud_point_index_idx
875+
{
876+
unsigned int idx;
877+
unsigned int cloud_point_index;
878+
879+
cloud_point_index_idx() = default;
880+
cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {}
881+
bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); }
882+
};
883+
}
869884
}
870885

871886
#ifdef PCL_NO_PRECOMPILE

filters/src/voxel_grid.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -420,7 +420,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
420420
div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
421421
div_b_[3] = 0;
422422

423-
std::vector<cloud_point_index_idx> index_vector;
423+
std::vector<internal::cloud_point_index_idx> index_vector;
424424
index_vector.reserve (indices_->size());
425425

426426
// Create the first xyz_offset, and set up the division multiplier
@@ -545,7 +545,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
545545

546546
// Second pass: sort the index_vector vector using value representing target cell as index
547547
// in effect all points belonging to the same output cell will be next to each other
548-
auto rightshift_func = [](const cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
548+
auto rightshift_func = [](const internal::cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
549549
boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func);
550550

551551
// Third pass: count output cells

filters/src/voxel_grid_label.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,9 @@
3737
*/
3838

3939
#include <map>
40+
#include <pcl/common/common.h> // for getMinMax3D
4041
#include <pcl/filters/voxel_grid_label.h>
41-
#include <pcl/filters/impl/voxel_grid.hpp>
42+
#include <boost/mpl/size.hpp> // for boost::mpl::size
4243

4344
//////////////////////////////////////////////////////////////////////////////
4445
void
@@ -111,7 +112,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)
111112
int label_index = -1;
112113
label_index = pcl::getFieldIndex<PointXYZRGBL> ("label", fields);
113114

114-
std::vector<cloud_point_index_idx> index_vector;
115+
std::vector<internal::cloud_point_index_idx> index_vector;
115116
index_vector.reserve(input_->size());
116117

117118
// If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...

registration/include/pcl/registration/transformation_estimation_svd.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ namespace registration {
5555
* \ingroup registration
5656
*/
5757
template <typename PointSource, typename PointTarget, typename Scalar = float>
58-
class TransformationEstimationSVD
58+
class PCL_EXPORTS TransformationEstimationSVD
5959
: public TransformationEstimation<PointSource, PointTarget, Scalar> {
6060
public:
6161
using Ptr = shared_ptr<TransformationEstimationSVD<PointSource, PointTarget, Scalar>>;

sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,6 @@
4242
#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PLANE_H_
4343

4444
#include <pcl/sample_consensus/sac_model_normal_plane.h>
45-
#include <pcl/sample_consensus/impl/sac_model_plane.hpp> // for dist4, dist8
4645
#include <pcl/common/common.h> // for getAngle3D
4746

4847
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////

sample_consensus/include/pcl/sample_consensus/impl/sac_model_plane.hpp

Lines changed: 0 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -117,36 +117,6 @@ pcl::SampleConsensusModelPlane<PointT>::computeModelCoefficients (
117117
return (true);
118118
}
119119

120-
#define AT(POS) ((*input_)[(*indices_)[(POS)]])
121-
122-
#ifdef __AVX__
123-
// This function computes the distances of 8 points to the plane
124-
template <typename PointT> inline __m256 pcl::SampleConsensusModelPlane<PointT>::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
125-
{
126-
// The andnot-function realizes an abs-operation: the sign bit is removed
127-
return _mm256_andnot_ps (abs_help,
128-
_mm256_add_ps (_mm256_add_ps (_mm256_mul_ps (a_vec, _mm256_set_ps (AT(i ).x, AT(i+1).x, AT(i+2).x, AT(i+3).x, AT(i+4).x, AT(i+5).x, AT(i+6).x, AT(i+7).x)),
129-
_mm256_mul_ps (b_vec, _mm256_set_ps (AT(i ).y, AT(i+1).y, AT(i+2).y, AT(i+3).y, AT(i+4).y, AT(i+5).y, AT(i+6).y, AT(i+7).y))),
130-
_mm256_add_ps (_mm256_mul_ps (c_vec, _mm256_set_ps (AT(i ).z, AT(i+1).z, AT(i+2).z, AT(i+3).z, AT(i+4).z, AT(i+5).z, AT(i+6).z, AT(i+7).z)),
131-
d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
132-
}
133-
#endif // ifdef __AVX__
134-
135-
#ifdef __SSE__
136-
// This function computes the distances of 4 points to the plane
137-
template <typename PointT> inline __m128 pcl::SampleConsensusModelPlane<PointT>::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
138-
{
139-
// The andnot-function realizes an abs-operation: the sign bit is removed
140-
return _mm_andnot_ps (abs_help,
141-
_mm_add_ps (_mm_add_ps (_mm_mul_ps (a_vec, _mm_set_ps (AT(i ).x, AT(i+1).x, AT(i+2).x, AT(i+3).x)),
142-
_mm_mul_ps (b_vec, _mm_set_ps (AT(i ).y, AT(i+1).y, AT(i+2).y, AT(i+3).y))),
143-
_mm_add_ps (_mm_mul_ps (c_vec, _mm_set_ps (AT(i ).z, AT(i+1).z, AT(i+2).z, AT(i+3).z)),
144-
d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
145-
}
146-
#endif // ifdef __SSE__
147-
148-
#undef AT
149-
150120
//////////////////////////////////////////////////////////////////////////
151121
template <typename PointT> void
152122
pcl::SampleConsensusModelPlane<PointT>::getDistancesToModel (

sample_consensus/include/pcl/sample_consensus/sac_model_plane.h

Lines changed: 27 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -139,7 +139,7 @@ namespace pcl
139139
* \ingroup sample_consensus
140140
*/
141141
template <typename PointT>
142-
class SampleConsensusModelPlane : public SampleConsensusModel<PointT>
142+
class PCL_EXPORTS SampleConsensusModelPlane : public SampleConsensusModel<PointT>
143143
{
144144
public:
145145
using SampleConsensusModel<PointT>::model_name_;
@@ -292,13 +292,35 @@ namespace pcl
292292
std::size_t i = 0) const;
293293
#endif
294294

295+
#define PCLAT(POS) ((*input_)[(*indices_)[(POS)]])
296+
295297
#ifdef __AVX__
296-
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;
297-
#endif
298+
// This function computes the distances of 8 points to the plane
299+
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
300+
{
301+
// The andnot-function realizes an abs-operation: the sign bit is removed
302+
return _mm256_andnot_ps (abs_help,
303+
_mm256_add_ps (_mm256_add_ps (_mm256_mul_ps (a_vec, _mm256_set_ps (PCLAT(i ).x, PCLAT(i+1).x, PCLAT(i+2).x, PCLAT(i+3).x, PCLAT(i+4).x, PCLAT(i+5).x, PCLAT(i+6).x, PCLAT(i+7).x)),
304+
_mm256_mul_ps (b_vec, _mm256_set_ps (PCLAT(i ).y, PCLAT(i+1).y, PCLAT(i+2).y, PCLAT(i+3).y, PCLAT(i+4).y, PCLAT(i+5).y, PCLAT(i+6).y, PCLAT(i+7).y))),
305+
_mm256_add_ps (_mm256_mul_ps (c_vec, _mm256_set_ps (PCLAT(i ).z, PCLAT(i+1).z, PCLAT(i+2).z, PCLAT(i+3).z, PCLAT(i+4).z, PCLAT(i+5).z, PCLAT(i+6).z, PCLAT(i+7).z)),
306+
d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
307+
}
308+
#endif // ifdef __AVX__
298309

299310
#ifdef __SSE__
300-
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;
301-
#endif
311+
// This function computes the distances of 4 points to the plane
312+
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
313+
{
314+
// The andnot-function realizes an abs-operation: the sign bit is removed
315+
return _mm_andnot_ps (abs_help,
316+
_mm_add_ps (_mm_add_ps (_mm_mul_ps (a_vec, _mm_set_ps (PCLAT(i ).x, PCLAT(i+1).x, PCLAT(i+2).x, PCLAT(i+3).x)),
317+
_mm_mul_ps (b_vec, _mm_set_ps (PCLAT(i ).y, PCLAT(i+1).y, PCLAT(i+2).y, PCLAT(i+3).y))),
318+
_mm_add_ps (_mm_mul_ps (c_vec, _mm_set_ps (PCLAT(i ).z, PCLAT(i+1).z, PCLAT(i+2).z, PCLAT(i+3).z)),
319+
d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
320+
}
321+
#endif // ifdef __SSE__
322+
323+
#undef PCLAT
302324

303325
private:
304326
/** \brief Check if a sample of indices results in a good sample of points

tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,8 @@ namespace tracking {
1111
* \ingroup tracking
1212
*/
1313
template <typename PointInT>
14-
class NearestPairPointCloudCoherence : public PointCloudCoherence<PointInT> {
14+
class PCL_EXPORTS NearestPairPointCloudCoherence
15+
: public PointCloudCoherence<PointInT> {
1516
public:
1617
using PointCloudCoherence<PointInT>::getClassName;
1718
using PointCloudCoherence<PointInT>::coherence_name_;

visualization/include/pcl/visualization/common/ren_win_interact_map.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@
3838

3939
#pragma once
4040

41+
#include <pcl/pcl_exports.h>
42+
4143
#include <map>
4244
#include <string>
4345

@@ -53,7 +55,7 @@ namespace pcl
5355
{
5456
namespace visualization
5557
{
56-
class RenWinInteract
58+
class PCL_EXPORTS RenWinInteract
5759
{
5860
public:
5961

0 commit comments

Comments
 (0)