-
-
Notifications
You must be signed in to change notification settings - Fork 4.6k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Missing pcl::MovingLeastSquaresOMP declaration without /openmp #2324
Changes from 2 commits
e694af7
305c7ee
9c97c33
1032788
9a14555
828b2e9
ee75335
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -92,7 +92,6 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::process (PointCloudOut &output) | |
if (!initCompute ()) | ||
return; | ||
|
||
|
||
// Initialize the spatial locator | ||
if (!tree_) | ||
{ | ||
|
@@ -284,65 +283,21 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::performProcessing (PointCloudOut & | |
// Compute the number of coefficients | ||
nr_coeff_ = (order_ + 1) * (order_ + 2) / 2; | ||
|
||
// Allocate enough space to hold the results of nearest neighbor searches | ||
// \note resize is irrelevant for a radiusSearch (). | ||
std::vector<int> nn_indices; | ||
std::vector<float> nn_sqr_dists; | ||
|
||
size_t mls_result_index = 0; | ||
|
||
// For all points | ||
for (size_t cp = 0; cp < indices_->size (); ++cp) | ||
{ | ||
// Get the initial estimates of point positions and their neighborhoods | ||
if (!searchForNeighbors ((*indices_)[cp], nn_indices, nn_sqr_dists)) | ||
continue; | ||
|
||
|
||
// Check the number of nearest neighbors for normal estimation (and later | ||
// for polynomial fit as well) | ||
if (nn_indices.size () < 3) | ||
continue; | ||
|
||
|
||
PointCloudOut projected_points; | ||
NormalCloud projected_points_normals; | ||
// Get a plane approximating the local surface's tangent and project point onto it | ||
int index = (*indices_)[cp]; | ||
|
||
if (cache_mls_results_) | ||
mls_result_index = index; // otherwise we give it a dummy location. | ||
|
||
computeMLSPointNormal (index, nn_indices, projected_points, projected_points_normals, *corresponding_input_indices_, mls_results_[mls_result_index]); | ||
|
||
// Append projected points to output | ||
output.insert (output.end (), projected_points.begin (), projected_points.end ()); | ||
if (compute_normals_) | ||
normals_->insert (normals_->end (), projected_points_normals.begin (), projected_points_normals.end ()); | ||
} | ||
|
||
// Perform the distinct-cloud or voxel-grid upsampling | ||
performUpsampling (output); | ||
} | ||
|
||
////////////////////////////////////////////////////////////////////////////////////////////// | ||
#ifdef _OPENMP | ||
template <typename PointInT, typename PointOutT> void | ||
pcl::MovingLeastSquaresOMP<PointInT, PointOutT>::performProcessing (PointCloudOut &output) | ||
{ | ||
// Compute the number of coefficients | ||
nr_coeff_ = (order_ + 1) * (order_ + 2) / 2; | ||
|
||
// (Maximum) number of threads | ||
unsigned int threads = threads_ == 0 ? 1 : threads_; | ||
|
||
const unsigned int threads = threads_ == 0 ? 1 : threads_; | ||
// Create temporaries for each thread in order to avoid synchronization | ||
typename PointCloudOut::CloudVectorType projected_points (threads); | ||
typename NormalCloud::CloudVectorType projected_points_normals (threads); | ||
std::vector<PointIndices> corresponding_input_indices (threads); | ||
typename PointCloudOut::CloudVectorType projected_points(threads); | ||
typename NormalCloud::CloudVectorType projected_points_normals(threads); | ||
std::vector<PointIndices> corresponding_input_indices(threads); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. We always have a space before parenthesis |
||
#endif | ||
|
||
// For all points | ||
#ifdef _OPENMP | ||
#pragma omp parallel for schedule (dynamic,1000) num_threads (threads) | ||
#endif | ||
for (int cp = 0; cp < static_cast<int> (indices_->size ()); ++cp) | ||
{ | ||
// Allocate enough space to hold the results of nearest neighbor searches | ||
|
@@ -351,35 +306,46 @@ pcl::MovingLeastSquaresOMP<PointInT, PointOutT>::performProcessing (PointCloudOu | |
std::vector<float> nn_sqr_dists; | ||
|
||
// Get the initial estimates of point positions and their neighborhoods | ||
if (this->searchForNeighbors ((*indices_)[cp], nn_indices, nn_sqr_dists)) | ||
if (searchForNeighbors ((*indices_)[cp], nn_indices, nn_sqr_dists)) | ||
{ | ||
// Check the number of nearest neighbors for normal estimation (and later | ||
// for polynomial fit as well) | ||
// Check the number of nearest neighbors for normal estimation (and later for polynomial fit as well) | ||
if (nn_indices.size () >= 3) | ||
{ | ||
// This thread's ID (range 0 to threads-1) | ||
int tn = omp_get_thread_num (); | ||
|
||
#ifdef _OPENMP | ||
const int tn = omp_get_thread_num (); | ||
// Size of projected points before computeMLSPointNormal () adds points | ||
size_t pp_size = projected_points[tn].size (); | ||
#else | ||
PointCloudOut projected_points; | ||
NormalCloud projected_points_normals; | ||
#endif | ||
|
||
// Get a plane approximating the local surface's tangent and project point onto it | ||
int index = (*indices_)[cp]; | ||
size_t mls_result_index = 0; | ||
|
||
if (this->cache_mls_results_) | ||
const int index = (*indices_)[cp]; | ||
|
||
if (cache_mls_results_) | ||
mls_result_index = index; // otherwise we give it a dummy location. | ||
|
||
this->computeMLSPointNormal (index, nn_indices, projected_points[tn], projected_points_normals[tn], corresponding_input_indices[tn], this->mls_results_[mls_result_index]); | ||
|
||
#ifdef _OPENMP | ||
computeMLSPointNormal(index, nn_indices, projected_points[tn], projected_points_normals[tn], corresponding_input_indices[tn], mls_results_[mls_result_index]); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. space |
||
|
||
// Copy all information from the input cloud to the output points (not doing any interpolation) | ||
for (size_t pp = pp_size; pp < projected_points[tn].size (); ++pp) | ||
this->copyMissingFields (input_->points[(*indices_)[cp]], projected_points[tn][pp]); | ||
} | ||
} | ||
copyMissingFields(input_->points[(*indices_)[cp]], projected_points[tn][pp]); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. space |
||
#else | ||
computeMLSPointNormal(index, nn_indices, projected_points, projected_points_normals, *corresponding_input_indices_, mls_results_[mls_result_index]); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. space |
||
|
||
// Append projected points to output | ||
output.insert(output.end (), projected_points.begin (), projected_points.end ()); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. space There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Sorry, missing space. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. There were more missing spaces. |
||
if (compute_normals_) | ||
normals_->insert(normals_->end (), projected_points_normals.begin (), projected_points_normals.end ()); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. space |
||
#endif | ||
} | ||
} | ||
} | ||
|
||
|
||
#ifdef _OPENMP | ||
// Combine all threads' results into the output vectors | ||
for (unsigned int tn = 0; tn < threads; ++tn) | ||
{ | ||
|
@@ -389,11 +355,11 @@ pcl::MovingLeastSquaresOMP<PointInT, PointOutT>::performProcessing (PointCloudOu | |
if (compute_normals_) | ||
normals_->insert (normals_->end (), projected_points_normals[tn].begin (), projected_points_normals[tn].end ()); | ||
} | ||
#endif | ||
|
||
// Perform the distinct-cloud or voxel-grid upsampling | ||
this->performUpsampling (output); | ||
performUpsampling (output); | ||
} | ||
#endif | ||
|
||
////////////////////////////////////////////////////////////////////////////////////////////// | ||
template <typename PointInT, typename PointOutT> void | ||
|
@@ -929,11 +895,7 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::copyMissingFields (const PointInT | |
point_out.z = temp.z; | ||
} | ||
|
||
|
||
#define PCL_INSTANTIATE_MovingLeastSquares(T,OutT) template class PCL_EXPORTS pcl::MovingLeastSquares<T,OutT>; | ||
|
||
#ifdef _OPENMP | ||
#define PCL_INSTANTIATE_MovingLeastSquaresOMP(T,OutT) template class PCL_EXPORTS pcl::MovingLeastSquaresOMP<T,OutT>; | ||
#endif | ||
|
||
#endif // PCL_SURFACE_IMPL_MLS_H_ |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -238,7 +238,11 @@ namespace pcl | |
* Reference paper: "Computing and Rendering Point Set Surfaces" by Marc Alexa, Johannes Behr, | ||
* Daniel Cohen-Or, Shachar Fleishman, David Levin and Claudio T. Silva | ||
* www.sci.utah.edu/~shachar/Publications/crpss.pdf | ||
* \author Zoltan Csaba Marton, Radu B. Rusu, Alexandru E. Ichim, Suat Gedikli | ||
* \note There is a parallelized version of the processing step, using the OpenMP standard. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This will produce three separate notes, is this intended? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I made this a single \note. |
||
* \note Compared to the standard version, an overhead is incurred in terms of runtime and memory usage. | ||
* \note The upsampling methods DISTINCT_CLOUD and VOXEL_GRID_DILATION are not parallelized completely, | ||
* i.e. parts of the algorithm run on a single thread only. | ||
* \author Zoltan Csaba Marton, Radu B. Rusu, Alexandru E. Ichim, Suat Gedikli, Robert Huitl | ||
* \ingroup surface | ||
*/ | ||
template <typename PointInT, typename PointOutT> | ||
|
@@ -303,6 +307,7 @@ namespace pcl | |
cache_mls_results_ (true), | ||
mls_results_ (), | ||
projection_method_ (MLSResult::SIMPLE), | ||
threads_(1), | ||
voxel_size_ (1.0), | ||
dilation_iteration_num_ (0), | ||
nr_coeff_ (), | ||
|
@@ -339,7 +344,7 @@ namespace pcl | |
|
||
/** \brief Set the order of the polynomial to be fit. | ||
* \param[in] order the order of the polynomial | ||
* \note Setting order > 1 indicates using a plynomial fit. | ||
* \note Setting order > 1 indicates using a polynomial fit. | ||
*/ | ||
inline void | ||
setPolynomialOrder (int order) { order_ = order; } | ||
|
@@ -510,6 +515,15 @@ namespace pcl | |
inline const std::vector<MLSResult>& | ||
getMLSResults () const { return (mls_results_); } | ||
|
||
/** \brief Set the maximum number of threads to use | ||
* \param threads the maximum number of hardware threads to use (0 sets the value to 1) | ||
*/ | ||
inline void | ||
setNumberOfThreads(unsigned int threads = 0) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. space between method and open parenthesis. |
||
{ | ||
threads_ = threads; | ||
} | ||
|
||
/** \brief Base method for surface reconstruction for all points given in <setInputCloud (), setIndices ()> | ||
* \param[out] output the resultant reconstructed surface model | ||
*/ | ||
|
@@ -578,6 +592,9 @@ namespace pcl | |
/** \brief Parameter that specifies the projection method to be used. */ | ||
MLSResult::ProjectionMethod projection_method_; | ||
|
||
/** \brief The maximum number of threads the scheduler should use. */ | ||
unsigned int threads_; | ||
|
||
|
||
/** \brief A minimalistic implementation of a voxel grid, necessary for the point cloud upsampling | ||
* \note Used only in the case of VOXEL_GRID_DILATION upsampling | ||
|
@@ -732,68 +749,23 @@ namespace pcl | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
}; | ||
|
||
#ifdef _OPENMP | ||
/** \brief MovingLeastSquaresOMP is a parallelized version of MovingLeastSquares, using the OpenMP standard. | ||
* \note Compared to MovingLeastSquares, an overhead is incurred in terms of runtime and memory usage. | ||
* \note The upsampling methods DISTINCT_CLOUD and VOXEL_GRID_DILATION are not parallelized completely, i.e. parts of the algorithm run on a single thread only. | ||
* \author Robert Huitl | ||
* \ingroup surface | ||
*/ | ||
/** \brief MovingLeastSquaresOMP implementation has been merged into MovingLeastSquares for better maintainability. | ||
* \note Keeping this empty child class for backwards compatibility. | ||
* \author Robert Huitl | ||
* \ingroup surface | ||
*/ | ||
template <typename PointInT, typename PointOutT> | ||
class MovingLeastSquaresOMP: public MovingLeastSquares<PointInT, PointOutT> | ||
class MovingLeastSquaresOMP : public MovingLeastSquares<PointInT, PointOutT> | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Add a deprecation macro here, something like class PCL_DEPRECATED_CLASS(MovingLeastSquaresOMP, "MovingLeastSquaresOMP and MovingLeastSquares have been merged, please use the latter") : public MovingLeastSquares<PointInT, PointOutT> You'll need to include There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I have tried this macro before, but the problem is that it generates a warning as soon as you include the header file, even if you aren't using the class. Which leads me to your next question:
Wouldn't that mean that developer's who use MovingLeastSquaresOMP and link the precompiled PCL libraries will get a linker error? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Which compiler is that? I added this deprecation macro, disabled OMP preinstantiation, and compiled There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. You are right, GCC behaves as expected and warns only if the class is actually used, but Visual Studio 2015 shows the behavior I described. Here's the full output:
For some reason, the class is still being instantiated, even after removing the macro in mls.cpp and changing my code to use the base class. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Just to clarify, this pops up even when building the library itself, i.e. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yes it does. |
||
{ | ||
public: | ||
typedef boost::shared_ptr<MovingLeastSquaresOMP<PointInT, PointOutT> > Ptr; | ||
typedef boost::shared_ptr<const MovingLeastSquaresOMP<PointInT, PointOutT> > ConstPtr; | ||
|
||
using MovingLeastSquares<PointInT, PointOutT>::VOXEL_GRID_DILATION; | ||
using MovingLeastSquares<PointInT, PointOutT>::DISTINCT_CLOUD; | ||
|
||
typedef pcl::PointCloud<pcl::Normal> NormalCloud; | ||
typedef pcl::PointCloud<pcl::Normal>::Ptr NormalCloudPtr; | ||
|
||
typedef pcl::PointCloud<PointOutT> PointCloudOut; | ||
typedef typename PointCloudOut::Ptr PointCloudOutPtr; | ||
typedef typename PointCloudOut::ConstPtr PointCloudOutConstPtr; | ||
|
||
/** \brief Constructor for parallelized Moving Least Squares | ||
* \param threads the maximum number of hardware threads to use (0 sets the value to 1) | ||
*/ | ||
MovingLeastSquaresOMP (unsigned int threads = 0) : threads_ (threads) | ||
{ | ||
|
||
} | ||
|
||
/** \brief Set the maximum number of threads to use | ||
* \param threads the maximum number of hardware threads to use (0 sets the value to 1) | ||
*/ | ||
inline void | ||
setNumberOfThreads (unsigned int threads = 0) | ||
{ | ||
threads_ = threads; | ||
} | ||
|
||
protected: | ||
using PCLBase<PointInT>::input_; | ||
using PCLBase<PointInT>::indices_; | ||
using MovingLeastSquares<PointInT, PointOutT>::normals_; | ||
using MovingLeastSquares<PointInT, PointOutT>::corresponding_input_indices_; | ||
using MovingLeastSquares<PointInT, PointOutT>::nr_coeff_; | ||
using MovingLeastSquares<PointInT, PointOutT>::order_; | ||
using MovingLeastSquares<PointInT, PointOutT>::compute_normals_; | ||
using MovingLeastSquares<PointInT, PointOutT>::upsample_method_; | ||
using MovingLeastSquares<PointInT, PointOutT>::cache_mls_results_; | ||
|
||
/** \brief Abstract surface reconstruction method. | ||
* \param[out] output the result of the reconstruction | ||
*/ | ||
virtual void | ||
performProcessing (PointCloudOut &output); | ||
|
||
/** \brief The maximum number of threads the scheduler should use. */ | ||
unsigned int threads_; | ||
public: | ||
/** \brief Constructor for parallelized Moving Least Squares | ||
* \param threads the maximum number of hardware threads to use (0 sets the value to 1) | ||
*/ | ||
MovingLeastSquaresOMP(unsigned int threads = 0) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. spacing |
||
{ | ||
this->setNumberOfThreads(threads); | ||
} | ||
}; | ||
#endif | ||
} | ||
|
||
#ifdef PCL_NO_PRECOMPILE | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This is not needed?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
You mean the added "const"?
I try to "Use const whenever it makes sense.": https://google.github.io/styleguide/cppguide.html#Use_of_const
In this case it's important that the variable does never change, as it defines the size of the vectors for the temporary data.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No,
const
is alright. I meant why not usingthreads_
directly since OpenMP does not differentiate between 0 and 1. But after a second look I can answer this question myself, this is needed to ensure vectors are properly sized.Yet on the other hand, wouldn't it be cleaner if we don't allow
threads_
to be zero?