Skip to content

Commit

Permalink
Merge pull request #5845 from mvieth/misc12
Browse files Browse the repository at this point in the history
Misc fixes and improvements
  • Loading branch information
mvieth authored Oct 19, 2023
2 parents 1cb996a + 2e78e75 commit 54a5b4a
Show file tree
Hide file tree
Showing 27 changed files with 111 additions and 47 deletions.
6 changes: 3 additions & 3 deletions .ci/azure-pipelines/azure-pipelines.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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'
Expand Down
6 changes: 3 additions & 3 deletions .ci/azure-pipelines/ubuntu-variety.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
4 changes: 4 additions & 0 deletions PCLConfig.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
12 changes: 6 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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] <br> [![Status][ci-ubuntu-20.04]][ci-latest-build] <br> [![Status][ci-ubuntu-22.04]][ci-latest-build] |
Ubuntu | [![Status][ci-ubuntu-20.04]][ci-latest-build] <br> [![Status][ci-ubuntu-22.04]][ci-latest-build] <br> [![Status][ci-ubuntu-23.04]][ci-latest-build] |
Windows | [![Status][ci-windows-x86]][ci-latest-build] <br> [![Status][ci-windows-x64]][ci-latest-build] |
macOS | [![Status][ci-macos-11]][ci-latest-build] <br> [![Status][ci-macos-12]][ci-latest-build] |
macOS | [![Status][ci-macos-11]][ci-latest-build] <br> [![Status][ci-macos-13]][ci-latest-build] |
Documentation | [![Status][ci-docs]][ci-latest-docs] |

Community
Expand Down
18 changes: 18 additions & 0 deletions common/include/pcl/point_representation.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<float> &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.
*/
Expand Down
4 changes: 2 additions & 2 deletions doc/tutorials/content/gasd_estimation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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)
Expand Down
11 changes: 6 additions & 5 deletions features/include/pcl/features/impl/gasd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,11 +76,12 @@ pcl::GASDEstimation<PointInT, PointOutT>::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;
Expand Down
3 changes: 3 additions & 0 deletions features/include/pcl/features/pfhrgb.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename PointInT, typename PointNT, typename PointOutT = pcl::PFHRGBSignature250>
class PFHRGBEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
{
Expand Down
3 changes: 2 additions & 1 deletion filters/include/pcl/filters/approximate_voxel_grid.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
*/
Expand Down
20 changes: 20 additions & 0 deletions gpu/features/src/features.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_;

Expand Down Expand Up @@ -145,6 +149,10 @@ void pcl::gpu::PFHEstimation::compute(const PointCloud& cloud, const Normals& no

void pcl::gpu::PFHEstimation::compute(DeviceArray2D<PFHSignature125>& 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);
Expand Down Expand Up @@ -183,6 +191,10 @@ void pcl::gpu::PFHRGBEstimation::compute(const PointCloud& cloud, const Normals&

void pcl::gpu::PFHRGBEstimation::compute(DeviceArray2D<PFHRGBSignature250>& 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);
Expand Down Expand Up @@ -231,6 +243,10 @@ void pcl::gpu::FPFHEstimation::compute(const PointCloud& cloud, const Normals& n

void pcl::gpu::FPFHEstimation::compute(DeviceArray2D<FPFHSignature33>& 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();

Expand Down Expand Up @@ -314,6 +330,10 @@ void pcl::gpu::PPFRGBEstimation::compute(DeviceArray<PPFRGBSignature>& features)

void pcl::gpu::PPFRGBRegionEstimation::compute(DeviceArray<PPFRGBSignature>& 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");

Expand Down
3 changes: 2 additions & 1 deletion gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/surface/texture_mapping.h>
#include <pcl/io/vtk_lib_io.h>
#include <pcl/io/ply_io.h>

using namespace pcl;

Expand Down Expand Up @@ -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<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromPCLPointCloud2(triangles.cloud, *cloud);
Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/ply/ply_parser.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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)) ||
Expand Down Expand Up @@ -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);
}
Expand Down Expand Up @@ -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);
}
Expand All @@ -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);
}
Expand All @@ -678,7 +678,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
istream.read (reinterpret_cast<char*> (&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);
}
Expand Down
12 changes: 6 additions & 6 deletions io/src/davidsdk_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,12 +281,12 @@ pcl::DavidSDKGrabber::grabSingleCloud (pcl::PointCloud<pcl::PointXYZ> &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")
Expand Down Expand Up @@ -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")
Expand Down Expand Up @@ -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")
Expand Down
3 changes: 2 additions & 1 deletion io/src/ply_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion recognition/include/pcl/recognition/implicit_shape_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
4 changes: 2 additions & 2 deletions registration/include/pcl/registration/gicp.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename PointT>
Expand Down
1 change: 1 addition & 0 deletions registration/include/pcl/registration/ndt.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename PointSource, typename PointTarget, typename Scalar = float>
class NormalDistributionsTransform
Expand Down
1 change: 1 addition & 0 deletions registration/include/pcl/registration/ndt_2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ namespace pcl {
* 2743–2748, Las Vegas, USA, October 2003.
*
* \author James Crosby
* \ingroup registration
*/
template <typename PointSource, typename PointTarget>
class NormalDistributionsTransform2D : public Registration<PointSource, PointTarget> {
Expand Down
1 change: 1 addition & 0 deletions registration/include/pcl/registration/ppf_registration.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
*/
Expand Down
Loading

0 comments on commit 54a5b4a

Please sign in to comment.