Skip to content

Commit

Permalink
Merge pull request #1 from PointCloudLibrary/master
Browse files Browse the repository at this point in the history
update
  • Loading branch information
greenbrettmichael authored Nov 6, 2018
2 parents 521a3ac + 164752b commit 02b7b16
Show file tree
Hide file tree
Showing 21 changed files with 199 additions and 59 deletions.
18 changes: 13 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,14 @@ elseif(MSVC)
set(CMAKE_COMPILER_IS_MSVC 1)
endif()

# Create a variable with expected default CXX flags
# This will be used further down the road to check if the user explicitly provided CXX flags
if(CMAKE_COMPILER_IS_MSVC)
set(CMAKE_CXX_FLAGS_DEFAULT "/DWIN32 /D_WINDOWS /W3 /GR /EHsc")
else()
set(CMAKE_CXX_FLAGS_DEFAULT "")
endif()

include("${PCL_SOURCE_DIR}/cmake/pcl_verbosity.cmake")
include("${PCL_SOURCE_DIR}/cmake/pcl_targets.cmake")
include("${PCL_SOURCE_DIR}/cmake/pcl_options.cmake")
Expand All @@ -114,13 +122,13 @@ endif()

# check for SSE flags
include("${PCL_SOURCE_DIR}/cmake/pcl_find_sse.cmake")
if(PCL_ENABLE_SSE AND "${CMAKE_CXX_FLAGS}" STREQUAL "")
if(PCL_ENABLE_SSE AND "${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
PCL_CHECK_FOR_SSE()
endif()

# ---[ Unix/Darwin/Windows specific flags
if(CMAKE_COMPILER_IS_GNUCXX)
if("${CMAKE_CXX_FLAGS}" STREQUAL "")
if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
SET(CMAKE_CXX_FLAGS "-Wall -Wextra -Wno-unknown-pragmas -fno-strict-aliasing -Wno-format-extra-args -Wno-sign-compare -Wno-invalid-offsetof -Wno-conversion ${SSE_FLAGS_STR}")

# Enable -Wabi for GCC > 4.3, and -Wno-deprecated for GCC < 4.3
Expand Down Expand Up @@ -159,7 +167,7 @@ endif()
if(CMAKE_COMPILER_IS_MSVC)
add_definitions("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX -DPCL_ONLY_CORE_POINT_TYPES /bigobj ${SSE_DEFINITIONS}")

if("${CMAKE_CXX_FLAGS}" STREQUAL "/DWIN32 /D_WINDOWS /W3 /GR /EHsc") # Check against default flags
if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /bigobj /fp:precise /wd4800 /wd4521 /wd4251 /wd4275 /wd4305 /wd4355 ${SSE_FLAGS_STR}")

# Add extra code generation/link optimizations
Expand Down Expand Up @@ -187,7 +195,7 @@ if(CMAKE_COMPILER_IS_MSVC)
endif()

if(CMAKE_COMPILER_IS_PATHSCALE)
if("${CMAKE_CXX_FLAGS}" STREQUAL "")
if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
SET(CMAKE_CXX_FLAGS "-Wno-uninitialized -zerouv -pthread -mp")
endif()
if("${CMAKE_SHARED_LINKER_FLAGS}" STREQUAL "")
Expand All @@ -196,7 +204,7 @@ if(CMAKE_COMPILER_IS_PATHSCALE)
endif()

if(CMAKE_COMPILER_IS_CLANG)
if("${CMAKE_C_FLAGS}" STREQUAL "")
if("${CMAKE_C_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
SET(CMAKE_C_FLAGS "-Qunused-arguments")
endif()
if("${CMAKE_CXX_FLAGS}" STREQUAL "")
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/common/impl/transforms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ namespace pcl
}
};

#if not defined(__AVX__)
#if !defined(__AVX__)

/** Optimized version for double-precision transform using SSE2 intrinsics. */
template<>
Expand Down
6 changes: 3 additions & 3 deletions common/include/pcl/point_types_conversion.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@

namespace pcl
{
// r,g,b, i values are from 0 to 1
// r,g,b, i values are from 0 to 255
// h = [0,360]
// s, v values are from 0 to 1
// if s = 0 > h = -1 (undefined)
// if s = 0 => h = 0

/** \brief Convert a XYZRGB point type to a XYZI
* \param[in] in the input XYZRGB point
Expand Down Expand Up @@ -153,7 +153,7 @@ namespace pcl
if (max == 0) // division by zero
{
out.s = 0.f;
out.h = 0.f; // h = -1.f;
out.h = 0.f;
return;
}

Expand Down
14 changes: 8 additions & 6 deletions features/include/pcl/features/fpfh_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,9 +60,9 @@ namespace pcl
* In Proceedings of the 22nd IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS),
* St. Louis, MO, USA, October 11-15 2009.
*
* \attention
* \attention
* The convention for FPFH features is:
* - if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN
* - if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN
* (not a number)
* - it is impossible to estimate a FPFH descriptor for a point that
* doesn't have finite 3D coordinates. Therefore, any point that contains
Expand Down Expand Up @@ -95,24 +95,26 @@ namespace pcl
/** \brief Initialize the scheduler and set the number of threads to use.
* \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
FPFHEstimationOMP (unsigned int nr_threads = 0) : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11), threads_ (nr_threads)
FPFHEstimationOMP (unsigned int nr_threads = 0) : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11)
{
feature_name_ = "FPFHEstimationOMP";

setNumberOfThreads(nr_threads);
}

/** \brief Initialize the scheduler and set the number of threads to use.
* \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
inline void
setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
void
setNumberOfThreads (unsigned int nr_threads = 0);

private:
/** \brief Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by
* <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in
* setSearchMethod ()
* \param[out] output the resultant point cloud model dataset that contains the FPFH feature estimates
*/
void
void
computeFeature (PointCloudOut &output);

public:
Expand Down
14 changes: 14 additions & 0 deletions features/include/pcl/features/impl/fpfh_omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,20 @@

#include <pcl/features/fpfh_omp.h>

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT> void
pcl::FPFHEstimationOMP<PointInT, PointNT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
{
if (nr_threads == 0)
#ifdef _OPENMP
threads_ = omp_get_num_procs();
#else
threads_ = 1;
#endif
else
threads_ = nr_threads;
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT> void
pcl::FPFHEstimationOMP<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
Expand Down
14 changes: 14 additions & 0 deletions features/include/pcl/features/impl/normal_3d_omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,20 @@

#include <pcl/features/normal_3d_omp.h>

///////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointOutT> void
pcl::NormalEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
{
if (nr_threads == 0)
#ifdef _OPENMP
threads_ = omp_get_num_procs();
#else
threads_ = 1;
#endif
else
threads_ = nr_threads;
}

///////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointOutT> void
pcl::NormalEstimationOMP<PointInT, PointOutT>::computeFeature (PointCloudOut &output)
Expand Down
18 changes: 16 additions & 2 deletions features/include/pcl/features/impl/shot_lrf_omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,22 @@
#include <pcl/features/shot_lrf_omp.h>
#include <pcl/features/shot_lrf.h>

template<typename PointInT, typename PointOutT>
void
//////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointInT, typename PointOutT> void
pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
{
if (nr_threads == 0)
#ifdef _OPENMP
threads_ = omp_get_num_procs();
#else
threads_ = 1;
#endif
else
threads_ = nr_threads;
}

//////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointInT, typename PointOutT> void
pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::computeFeature (PointCloudOut &output)
{
//check whether used with search radius or search k-neighbors
Expand Down
28 changes: 28 additions & 0 deletions features/include/pcl/features/impl/shot_omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,20 @@ pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::initCompute
return (true);
}

//////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::setNumberOfThreads (unsigned int nr_threads)
{
if (nr_threads == 0)
#ifdef _OPENMP
threads_ = omp_get_num_procs();
#else
threads_ = 1;
#endif
else
threads_ = nr_threads;
}

//////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (PointCloudOut &output)
Expand Down Expand Up @@ -189,6 +203,20 @@ pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (
}
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::setNumberOfThreads (unsigned int nr_threads)
{
if (nr_threads == 0)
#ifdef _OPENMP
threads_ = omp_get_num_procs();
#else
threads_ = 1;
#endif
else
threads_ = nr_threads;
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (PointCloudOut &output)
Expand Down
10 changes: 6 additions & 4 deletions features/include/pcl/features/normal_3d_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,16 +74,18 @@ namespace pcl
/** \brief Initialize the scheduler and set the number of threads to use.
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
NormalEstimationOMP (unsigned int nr_threads = 0) : threads_ (nr_threads)
NormalEstimationOMP (unsigned int nr_threads = 0)
{
feature_name_ = "NormalEstimationOMP";

setNumberOfThreads(nr_threads);
}

/** \brief Initialize the scheduler and set the number of threads to use.
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
inline void
setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
void
setNumberOfThreads (unsigned int nr_threads = 0);

protected:
/** \brief The number of threads the scheduler should use. */
Expand All @@ -94,7 +96,7 @@ namespace pcl
* setSearchSurface () and the spatial locator in setSearchMethod ()
* \param output the resultant point cloud model dataset that contains surface normals and curvatures
*/
void
void
computeFeature (PointCloudOut &output);
};
}
Expand Down
10 changes: 6 additions & 4 deletions features/include/pcl/features/shot_lrf_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,19 +70,21 @@ namespace pcl
typedef boost::shared_ptr<SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT> > Ptr;
typedef boost::shared_ptr<const SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT> > ConstPtr;
/** \brief Constructor */
SHOTLocalReferenceFrameEstimationOMP () : threads_ (0)
SHOTLocalReferenceFrameEstimationOMP ()
{
feature_name_ = "SHOTLocalReferenceFrameEstimationOMP";

setNumberOfThreads(0);
}

/** \brief Empty destructor */
virtual ~SHOTLocalReferenceFrameEstimationOMP () {}

/** \brief Initialize the scheduler and set the number of threads to use.
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
inline void
setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
void
setNumberOfThreads (unsigned int nr_threads = 0);

protected:
using Feature<PointInT, PointOutT>::feature_name_;
Expand Down
18 changes: 11 additions & 7 deletions features/include/pcl/features/shot_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,13 +96,16 @@ namespace pcl
typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;

/** \brief Empty constructor. */
SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> (), threads_ (nr_threads)
{ };
SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> ()
{
setNumberOfThreads(nr_threads);
};

/** \brief Initialize the scheduler and set the number of threads to use.
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
inline void
setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
void
setNumberOfThreads (unsigned int nr_threads = 0);

protected:

Expand Down Expand Up @@ -178,15 +181,16 @@ namespace pcl
SHOTColorEstimationOMP (bool describe_shape = true,
bool describe_color = true,
unsigned int nr_threads = 0)
: SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> (describe_shape, describe_color), threads_ (nr_threads)
: SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> (describe_shape, describe_color)
{
setNumberOfThreads(nr_threads);
}

/** \brief Initialize the scheduler and set the number of threads to use.
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
inline void
setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
void
setNumberOfThreads (unsigned int nr_threads = 0);

protected:

Expand Down
13 changes: 7 additions & 6 deletions filters/include/pcl/filters/fast_bilateral_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,27 +68,28 @@ namespace pcl
typedef typename Filter<PointT>::PointCloud PointCloud;

public:

typedef boost::shared_ptr< FastBilateralFilterOMP<PointT> > Ptr;
typedef boost::shared_ptr< const FastBilateralFilterOMP<PointT> > ConstPtr;

/** \brief Empty constructor. */
FastBilateralFilterOMP (unsigned int nr_threads = 0)
: threads_ (nr_threads)
{ }
{
setNumberOfThreads(nr_threads);
}

/** \brief Initialize the scheduler and set the number of threads to use.
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
*/
inline void
setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
void
setNumberOfThreads (unsigned int nr_threads = 0);

/** \brief Filter the input data and store the results into output.
* \param[out] output the resultant point cloud
*/
void
applyFilter (PointCloud &output);

protected:
/** \brief The number of threads the scheduler should use. */
unsigned int threads_;
Expand Down
14 changes: 14 additions & 0 deletions filters/include/pcl/filters/impl/fast_bilateral_omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,20 @@
#include <pcl/console/time.h>
#include <assert.h>

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointT> void
pcl::FastBilateralFilterOMP<PointT>::setNumberOfThreads (unsigned int nr_threads)
{
if (nr_threads == 0)
#ifdef _OPENMP
threads_ = omp_get_num_procs();
#else
threads_ = 1;
#endif
else
threads_ = nr_threads;
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointT> void
pcl::FastBilateralFilterOMP<PointT>::applyFilter (PointCloud &output)
Expand Down
Loading

0 comments on commit 02b7b16

Please sign in to comment.