diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml
index bb3c54e6a70..c40dbae510d 100644
--- a/.ci/azure-pipelines/azure-pipelines.yaml
+++ b/.ci/azure-pipelines/azure-pipelines.yaml
@@ -76,9 +76,9 @@ stages:
Big Sur 11:
VMIMAGE: 'macOS-11'
OSX_VERSION: '11'
- Monterey 12:
- VMIMAGE: 'macOS-12'
- OSX_VERSION: '12'
+ Ventura 13:
+ VMIMAGE: 'macOS-13'
+ OSX_VERSION: '13'
timeoutInMinutes: 0
variables:
BUILD_DIR: '$(Agent.WorkFolder)/build'
diff --git a/.ci/azure-pipelines/ubuntu-variety.yaml b/.ci/azure-pipelines/ubuntu-variety.yaml
index e085ba0346d..e836a655c7b 100644
--- a/.ci/azure-pipelines/ubuntu-variety.yaml
+++ b/.ci/azure-pipelines/ubuntu-variety.yaml
@@ -32,9 +32,9 @@ jobs:
POSSIBLE_VTK_VERSION=("9") \
POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \
POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \
- POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \
- POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \
- POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16") \
+ POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \
+ POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \
+ POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16" "clang++-17") \
CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \
dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]} --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \
echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs"
diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in
index aede14383b2..1c8a1bd59c9 100644
--- a/PCLConfig.cmake.in
+++ b/PCLConfig.cmake.in
@@ -120,6 +120,10 @@ macro(find_eigen3)
if(NOT EIGEN3_FOUND AND Eigen3_FOUND)
set(EIGEN3_FOUND ${Eigen3_FOUND})
endif()
+ # In very new Eigen versions, EIGEN3_INCLUDE_DIR(S) is not defined any more, only the target:
+ if(TARGET Eigen3::Eigen)
+ set(EIGEN3_LIBRARIES Eigen3::Eigen)
+ endif()
endmacro()
#remove this as soon as qhull is shipped with FindQhull.cmake
diff --git a/README.md b/README.md
index ca2b0d9b9fd..5301c088978 100644
--- a/README.md
+++ b/README.md
@@ -21,21 +21,21 @@ If you really need access to the old website, please use [the copy made by the i
Continuous integration
----------------------
[ci-latest-build]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=9&branchName=master
-[ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2020.04%20Clang&label=Ubuntu%2020.04%20Clang
-[ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2022.04%20GCC&label=Ubuntu%2022.04%20GCC
-[ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2022.04%20GCC&label=Ubuntu%2023.04%20GCC
+[ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2020.04%20GCC&label=Ubuntu%2020.04%20GCC
+[ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2022.04%20Clang&label=Ubuntu%2022.04%20Clang
+[ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2023.04%20GCC&label=Ubuntu%2023.04%20GCC
[ci-windows-x86]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x86&label=Windows%20VS2019%20x86
[ci-windows-x64]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x64&label=Windows%20VS2019%20x64
[ci-macos-11]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Big%20Sur%2011&label=macOS%20Big%20Sur%2011
-[ci-macos-12]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Monterey%2012&label=macOS%20Monterey%2012
+[ci-macos-13]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Ventura%2013&label=macOS%20Ventura%2013
[ci-docs]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/Documentation?branchName=master
[ci-latest-docs]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=14&branchName=master
Build Platform | Status
------------------------ | ------------------------------------------------------------------------------------------------- |
-Ubuntu | [![Status][ci-ubuntu-18.04]][ci-latest-build]
[![Status][ci-ubuntu-20.04]][ci-latest-build]
[![Status][ci-ubuntu-22.04]][ci-latest-build] |
+Ubuntu | [![Status][ci-ubuntu-20.04]][ci-latest-build]
[![Status][ci-ubuntu-22.04]][ci-latest-build]
[![Status][ci-ubuntu-23.04]][ci-latest-build] |
Windows | [![Status][ci-windows-x86]][ci-latest-build]
[![Status][ci-windows-x64]][ci-latest-build] |
-macOS | [![Status][ci-macos-11]][ci-latest-build]
[![Status][ci-macos-12]][ci-latest-build] |
+macOS | [![Status][ci-macos-11]][ci-latest-build]
[![Status][ci-macos-13]][ci-latest-build] |
Documentation | [![Status][ci-docs]][ci-latest-docs] |
Community
diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h
index 3d918a86df1..17b2a0d422c 100644
--- a/common/include/pcl/point_representation.h
+++ b/common/include/pcl/point_representation.h
@@ -158,6 +158,24 @@ namespace pcl
delete [] temp;
}
+ void
+ vectorize (const PointT &p, float* out) const
+ {
+ copyToFloatArray (p, out);
+ if (!alpha_.empty ())
+ for (int i = 0; i < nr_dimensions_; ++i)
+ out[i] *= alpha_[i];
+ }
+
+ void
+ vectorize (const PointT &p, std::vector &out) const
+ {
+ copyToFloatArray (p, out.data());
+ if (!alpha_.empty ())
+ for (int i = 0; i < nr_dimensions_; ++i)
+ out[i] *= alpha_[i];
+ }
+
/** \brief Set the rescale values to use when vectorizing points
* \param[in] rescale_array The array/vector of rescale values. Can be of any type that implements the [] operator.
*/
diff --git a/doc/tutorials/content/gasd_estimation.rst b/doc/tutorials/content/gasd_estimation.rst
index bc28188c385..f725e4ea69f 100644
--- a/doc/tutorials/content/gasd_estimation.rst
+++ b/doc/tutorials/content/gasd_estimation.rst
@@ -98,7 +98,7 @@ The following code snippet will estimate a GASD shape + color descriptor for an
gasd.compute (descriptor);
// Get the alignment transform
- Eigen::Matrix4f trans = gasd.getTransform (trans);
+ Eigen::Matrix4f trans = gasd.getTransform ();
// Unpack histogram bins
for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i)
@@ -131,7 +131,7 @@ The following code snippet will estimate a GASD shape only descriptor for an inp
gasd.compute (descriptor);
// Get the alignment transform
- Eigen::Matrix4f trans = gasd.getTransform (trans);
+ Eigen::Matrix4f trans = gasd.getTransform ();
// Unpack histogram bins
for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i)
diff --git a/features/include/pcl/features/impl/gasd.hpp b/features/include/pcl/features/impl/gasd.hpp
index 73074b63fbd..47522c57631 100644
--- a/features/include/pcl/features/impl/gasd.hpp
+++ b/features/include/pcl/features/impl/gasd.hpp
@@ -76,11 +76,12 @@ pcl::GASDEstimation::computeAlignmentTransform ()
Eigen::Vector4f centroid;
Eigen::Matrix3f covariance_matrix;
- // compute centroid of the object's partial view
- pcl::compute3DCentroid (*surface_, *indices_, centroid);
-
- // compute covariance matrix from points and centroid of the object's partial view
- pcl::computeCovarianceMatrix (*surface_, *indices_, centroid, covariance_matrix);
+ // compute centroid of the object's partial view, then compute covariance matrix from points and centroid of the object's partial view
+ if (pcl::compute3DCentroid (*surface_, *indices_, centroid) == 0 ||
+ pcl::computeCovarianceMatrix (*surface_, *indices_, centroid, covariance_matrix) == 0) {
+ PCL_ERROR("[pcl::GASDEstimation::computeAlignmentTransform] Surface cloud or indices are empty!\n");
+ return;
+ }
Eigen::Matrix3f eigenvectors;
Eigen::Vector3f eigenvalues;
diff --git a/features/include/pcl/features/pfhrgb.h b/features/include/pcl/features/pfhrgb.h
index f42f26e11b4..de87ce6bd94 100644
--- a/features/include/pcl/features/pfhrgb.h
+++ b/features/include/pcl/features/pfhrgb.h
@@ -43,6 +43,9 @@
namespace pcl
{
+ /** \brief Similar to the Point Feature Histogram descriptor, but also takes color into account. See also \ref PFHEstimation
+ * \ingroup features
+ */
template
class PFHRGBEstimation : public FeatureFromNormals
{
diff --git a/filters/include/pcl/filters/approximate_voxel_grid.h b/filters/include/pcl/filters/approximate_voxel_grid.h
index 4e1b6319513..95e16a1d868 100644
--- a/filters/include/pcl/filters/approximate_voxel_grid.h
+++ b/filters/include/pcl/filters/approximate_voxel_grid.h
@@ -90,7 +90,8 @@ namespace pcl
};
/** \brief ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
- *
+ * Thus, this is similar to the \ref VoxelGrid filter.
+ * This class works best if points that are stored in memory next to each other (in the input point cloud), are also somewhat close in 3D euclidean space (this is for example usually the case for organized point clouds). If the points have no storage order (e.g. in synthetic, randomly generated point clouds), this class will give very poor results, and \ref VoxelGrid should be used instead.
* \author James Bowman, Radu B. Rusu
* \ingroup filters
*/
diff --git a/gpu/features/src/features.cpp b/gpu/features/src/features.cpp
index a0172c3a2cb..5f356ef94df 100644
--- a/gpu/features/src/features.cpp
+++ b/gpu/features/src/features.cpp
@@ -103,6 +103,10 @@ void pcl::gpu::NormalEstimation::getViewPoint (float &vpx, float &vpy, float &vp
void pcl::gpu::NormalEstimation::compute(Normals& normals)
{
assert(!cloud_.empty());
+ if (radius_ <= 0.0f || max_results_ <= 0) {
+ pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+ return;
+ }
PointCloud& surface = surface_.empty() ? cloud_ : surface_;
@@ -145,6 +149,10 @@ void pcl::gpu::PFHEstimation::compute(const PointCloud& cloud, const Normals& no
void pcl::gpu::PFHEstimation::compute(DeviceArray2D& features)
{
+ if (radius_ <= 0.0f || max_results_ <= 0) {
+ pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+ return;
+ }
PointCloud& surface = surface_.empty() ? cloud_ : surface_;
octree_.setCloud(surface);
@@ -183,6 +191,10 @@ void pcl::gpu::PFHRGBEstimation::compute(const PointCloud& cloud, const Normals&
void pcl::gpu::PFHRGBEstimation::compute(DeviceArray2D& features)
{
+ if (radius_ <= 0.0f || max_results_ <= 0) {
+ pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+ return;
+ }
PointCloud& surface = surface_.empty() ? cloud_ : surface_;
octree_.setCloud(surface);
@@ -231,6 +243,10 @@ void pcl::gpu::FPFHEstimation::compute(const PointCloud& cloud, const Normals& n
void pcl::gpu::FPFHEstimation::compute(DeviceArray2D& features)
{
+ if (radius_ <= 0.0f || max_results_ <= 0) {
+ pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+ return;
+ }
bool hasInds = !indices_.empty() && indices_.size() != cloud_.size();
bool hasSurf = !surface_.empty();
@@ -314,6 +330,10 @@ void pcl::gpu::PPFRGBEstimation::compute(DeviceArray& features)
void pcl::gpu::PPFRGBRegionEstimation::compute(DeviceArray& features)
{
+ if (radius_ <= 0.0f || max_results_ <= 0) {
+ pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+ return;
+ }
static_assert(sizeof(PPFRGBRegionEstimation:: PointType) == sizeof(device:: PointType), "Point sizes do not match");
static_assert(sizeof(PPFRGBRegionEstimation::NormalType) == sizeof(device::NormalType), "Normal sizes do not match");
diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp
index 657927043c1..d1570464c87 100644
--- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp
+++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp
@@ -48,6 +48,7 @@
#include
#include
#include
+#include
using namespace pcl;
@@ -405,7 +406,7 @@ main (int argc, char** argv)
// read mesh from plyfile
PCL_INFO ("\nLoading mesh from file %s...\n", argv[1]);
pcl::PolygonMesh triangles;
- pcl::io::loadPolygonFilePLY(argv[1], triangles);
+ pcl::io::loadPLYFile(argv[1], triangles);
pcl::PointCloud::Ptr cloud (new pcl::PointCloud);
pcl::fromPCLPointCloud2(triangles.cloud, *cloud);
diff --git a/io/include/pcl/io/ply/ply_parser.h b/io/include/pcl/io/ply/ply_parser.h
index 2e0390072af..3023d566607 100644
--- a/io/include/pcl/io/ply/ply_parser.h
+++ b/io/include/pcl/io/ply/ply_parser.h
@@ -563,7 +563,7 @@ inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format,
if (!istream || !isspace (space))
{
if (error_callback_)
- error_callback_ (line_number_, "parse error");
+ error_callback_ (line_number_, "error while parsing scalar property (file format: ascii)");
return (false);
}
if (scalar_property_callback)
@@ -575,7 +575,7 @@ inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format,
if (!istream)
{
if (error_callback_)
- error_callback_ (line_number_, "parse error");
+ error_callback_ (line_number_, "error while parsing scalar property (file format: binary)");
return (false);
}
if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) ||
@@ -608,7 +608,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
{
if (error_callback_)
{
- error_callback_ (line_number_, "parse error");
+ error_callback_ (line_number_, "error while parsing list (file format: ascii)");
}
return (false);
}
@@ -639,7 +639,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
{
if (error_callback_)
{
- error_callback_ (line_number_, "parse error");
+ error_callback_ (line_number_, "error while parsing list (file format: ascii)");
}
return (false);
}
@@ -665,7 +665,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
{
if (error_callback_)
{
- error_callback_ (line_number_, "parse error");
+ error_callback_ (line_number_, "error while parsing list (file format: binary)");
}
return (false);
}
@@ -678,7 +678,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
istream.read (reinterpret_cast (&value), sizeof (scalar_type));
if (!istream) {
if (error_callback_) {
- error_callback_ (line_number_, "parse error");
+ error_callback_ (line_number_, "error while parsing list (file format: binary)");
}
return (false);
}
diff --git a/io/src/davidsdk_grabber.cpp b/io/src/davidsdk_grabber.cpp
index d13fb4663d7..4c3da25fedd 100644
--- a/io/src/davidsdk_grabber.cpp
+++ b/io/src/davidsdk_grabber.cpp
@@ -281,12 +281,12 @@ pcl::DavidSDKGrabber::grabSingleCloud (pcl::PointCloud &cloud)
pcl::PolygonMesh mesh;
if (file_format_ == "obj")
{
- if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, mesh) == 0)
+ if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, mesh) == 0)
return (false);
}
else if (file_format_ == "ply")
{
- if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, mesh) == 0)
+ if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, mesh) == 0)
return (false);
}
else if (file_format_ == "stl")
@@ -323,12 +323,12 @@ pcl::DavidSDKGrabber::grabSingleMesh (pcl::PolygonMesh &mesh)
if (file_format_ == "obj")
{
- if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, mesh) == 0)
+ if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, mesh) == 0)
return (false);
}
else if (file_format_ == "ply")
{
- if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, mesh) == 0)
+ if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, mesh) == 0)
return (false);
}
else if (file_format_ == "stl")
@@ -400,12 +400,12 @@ pcl::DavidSDKGrabber::processGrabbing ()
if (file_format_ == "obj")
{
- if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, *mesh) == 0)
+ if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, *mesh) == 0)
return;
}
else if (file_format_ == "ply")
{
- if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, *mesh) == 0)
+ if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, *mesh) == 0)
return;
}
else if (file_format_ == "stl")
diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp
index b8c94329723..aaedca8f39d 100644
--- a/io/src/ply_io.cpp
+++ b/io/src/ply_io.cpp
@@ -566,7 +566,7 @@ pcl::PLYReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
orientation_ = Eigen::Matrix3f::Identity ();
if (!parse (file_name))
{
- PCL_ERROR ("[pcl::PLYReader::read] problem parsing header!\n");
+ PCL_ERROR ("[pcl::PLYReader::readHeader] problem parsing header!\n");
return (-1);
}
cloud_->row_step = cloud_->point_step * cloud_->width;
@@ -676,6 +676,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
Eigen::Vector4f &origin, Eigen::Quaternionf &orientation,
int &ply_version, const int offset)
{
+ PCL_DEBUG("[pcl::PLYReader::read] Reading PolygonMesh from file: %s.\n", file_name.c_str());
// kept only for backward compatibility
int data_type;
unsigned int data_idx;
diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h
index 652200dd596..c32f55150f4 100644
--- a/recognition/include/pcl/recognition/implicit_shape_model.h
+++ b/recognition/include/pcl/recognition/implicit_shape_model.h
@@ -227,7 +227,7 @@ namespace pcl
{
/** \brief This class implements Implicit Shape Model algorithm described in
* "Hough Transforms and 3D SURF for robust three dimensional classication"
- * by Jan Knopp1, Mukta Prasad, Geert Willems1, Radu Timofte, and Luc Van Gool.
+ * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool.
* It has two main member functions. One for training, using the data for which we know
* which class it belongs to. And second for investigating a cloud for the presence
* of the class of interest.
diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h
index 2eae855abbf..b0fad8046cb 100644
--- a/registration/include/pcl/registration/gicp.h
+++ b/registration/include/pcl/registration/gicp.h
@@ -381,8 +381,8 @@ class GeneralizedIterativeClosestPoint
/** \brief compute points covariances matrices according to the K nearest
* neighbors. K is set via setCorrespondenceRandomness() method.
- * \param cloud pointer to point cloud
- * \param tree KD tree performer for nearest neighbors search
+ * \param[in] cloud pointer to point cloud
+ * \param[in] tree KD tree performer for nearest neighbors search
* \param[out] cloud_covariances covariances matrices for each point in the cloud
*/
template
diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h
index fbe2b16f5b5..81788ed687d 100644
--- a/registration/include/pcl/registration/ndt.h
+++ b/registration/include/pcl/registration/ndt.h
@@ -60,6 +60,7 @@ namespace pcl {
* Optimization Theory and Methods: Nonlinear Programming. 89-100
* \note Math refactored by Todor Stoyanov.
* \author Brian Okorn (Space and Naval Warfare Systems Center Pacific)
+ * \ingroup registration
*/
template
class NormalDistributionsTransform
diff --git a/registration/include/pcl/registration/ndt_2d.h b/registration/include/pcl/registration/ndt_2d.h
index 8b3a927a84b..e65af5ab192 100644
--- a/registration/include/pcl/registration/ndt_2d.h
+++ b/registration/include/pcl/registration/ndt_2d.h
@@ -54,6 +54,7 @@ namespace pcl {
* 2743–2748, Las Vegas, USA, October 2003.
*
* \author James Crosby
+ * \ingroup registration
*/
template
class NormalDistributionsTransform2D : public Registration {
diff --git a/registration/include/pcl/registration/ppf_registration.h b/registration/include/pcl/registration/ppf_registration.h
index 81e783dd7f3..0e4bacea2ec 100644
--- a/registration/include/pcl/registration/ppf_registration.h
+++ b/registration/include/pcl/registration/ppf_registration.h
@@ -169,6 +169,7 @@ class PCL_EXPORTS PPFHashMapSearch {
* 13-18 June 2010, San Francisco, CA
*
* \note This class works in tandem with the PPFEstimation class
+ * \ingroup registration
*
* \author Alexandru-Eugen Ichim
*/
diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp
index 2f7118e7058..e0be7718f0d 100644
--- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp
+++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp
@@ -69,7 +69,7 @@ pcl::SampleConsensusModelCone::computeModelCoefficients (
if (!normals_)
{
- PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] No input dataset containing normals was given!\n");
+ PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] No input dataset containing normals was given! Use setInputNormals\n");
return (false);
}
diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp
index 03e26680a39..6ae067ad3c4 100644
--- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp
+++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp
@@ -84,7 +84,7 @@ pcl::SampleConsensusModelCylinder::computeModelCoefficients (
if (!normals_)
{
- PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given!\n");
+ PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given! Use setInputNormals\n");
return (false);
}
diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp
index 0e718f10072..94de2e7af8d 100644
--- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp
+++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp
@@ -251,7 +251,10 @@ pcl::SampleConsensusModelLine::projectPoints (
{
// Needs a valid model coefficients
if (!isModelValid (model_coefficients))
+ {
+ PCL_ERROR ("[pcl::SampleConsensusModelLine::projectPoints] Given model is invalid!\n");
return;
+ }
// Obtain the line point and direction
Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f);
diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp
index b83d0f70ec4..a29a7067baf 100644
--- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp
+++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp
@@ -51,7 +51,7 @@ pcl::SampleConsensusModelNormalSphere::selectWithinDistance (
{
if (!normals_)
{
- PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given!\n");
+ PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given! Use setInputNormals\n");
inliers.clear ();
return;
}
@@ -112,7 +112,7 @@ pcl::SampleConsensusModelNormalSphere::countWithinDistance (
{
if (!normals_)
{
- PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n");
+ PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given! Use setInputNormals\n");
return (0);
}
@@ -163,7 +163,7 @@ pcl::SampleConsensusModelNormalSphere::getDistancesToModel (
{
if (!normals_)
{
- PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n");
+ PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given! Use setInputNormals\n");
return;
}
diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h
index 1e15149953c..537fcb3d0dd 100644
--- a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h
+++ b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h
@@ -223,10 +223,14 @@ namespace pcl
if (!SampleConsensusModel::isModelValid (model_coefficients))
return (false);
- if (radius_min_ != -std::numeric_limits::max() && model_coefficients[3] < radius_min_)
+ if (radius_min_ != -std::numeric_limits::max() && model_coefficients[3] < radius_min_) {
+ PCL_DEBUG("[SampleConsensusModelSphere::isModelValid] Model radius %g is smaller than user specified minimum radius %g\n", model_coefficients[3], radius_min_);
return (false);
- if (radius_max_ != std::numeric_limits::max() && model_coefficients[3] > radius_max_)
+ }
+ if (radius_max_ != std::numeric_limits::max() && model_coefficients[3] > radius_max_) {
+ PCL_DEBUG("[SampleConsensusModelSphere::isModelValid] Model radius %g is bigger than user specified maximum radius %g\n", model_coefficients[3], radius_max_);
return (false);
+ }
return (true);
}
diff --git a/surface/include/pcl/surface/impl/grid_projection.hpp b/surface/include/pcl/surface/impl/grid_projection.hpp
index 7264ff26af6..c5e232fa606 100644
--- a/surface/include/pcl/surface/impl/grid_projection.hpp
+++ b/surface/include/pcl/surface/impl/grid_projection.hpp
@@ -319,7 +319,11 @@ pcl::GridProjection::getProjectionWithPlaneFit (const Eigen::Vector4f &
Eigen::Matrix3f covariance_matrix;
Eigen::Vector4f xyz_centroid;
- computeMeanAndCovarianceMatrix (*data_, pt_union_indices, covariance_matrix, xyz_centroid);
+ if (computeMeanAndCovarianceMatrix (*data_, pt_union_indices, covariance_matrix, xyz_centroid) == 0) {
+ PCL_ERROR("[pcl::GridProjection::getProjectionWithPlaneFit] cloud or indices are empty!\n");
+ projection = p;
+ return;
+ }
// Get the plane normal
EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value;
diff --git a/tools/mesh_sampling.cpp b/tools/mesh_sampling.cpp
index 79f916ce6fc..5472545cd31 100644
--- a/tools/mesh_sampling.cpp
+++ b/tools/mesh_sampling.cpp
@@ -38,6 +38,7 @@
#include
#include
#include
+#include
#include
#include
#include
@@ -244,7 +245,7 @@ main (int argc, char **argv)
if (ply_file_indices.size () == 1)
{
pcl::PolygonMesh mesh;
- pcl::io::loadPolygonFilePLY (argv[ply_file_indices[0]], mesh);
+ pcl::io::loadPLYFile (argv[ply_file_indices[0]], mesh);
pcl::io::mesh2vtk (mesh, polydata1);
}
else if (obj_file_indices.size () == 1)
diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp
index f2eb40e4ff7..06d8fbfbf11 100644
--- a/visualization/src/pcl_visualizer.cpp
+++ b/visualization/src/pcl_visualizer.cpp
@@ -1630,7 +1630,7 @@ pcl::visualization::PCLVisualizer::setPointCloudSelected (const bool selected, c
if (am_it == cloud_actor_map_->end ())
{
- pcl::console::print_error ("[setPointCloudRenderingProperties] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ());
+ pcl::console::print_error ("[setPointCloudSelected] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ());
return (false);
}
// Get the actor pointer