Skip to content

Commit

Permalink
Merge pull request #3711 from Morwenn/patch-1
Browse files Browse the repository at this point in the history
Add precompiled computeApproximateCovariances; fix compilation error for the same
  • Loading branch information
kunaltyagi committed Mar 15, 2020
2 parents 20a289b + 3a25fcc commit e6e7377
Show file tree
Hide file tree
Showing 3 changed files with 59 additions and 5 deletions.
1 change: 1 addition & 0 deletions features/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ set(srcs
src/crh.cpp
src/don.cpp
src/fpfh.cpp
src/from_meshes.cpp
src/gasd.cpp
src/gfpfh.cpp
src/integral_image_normal.cpp
Expand Down
13 changes: 8 additions & 5 deletions features/include/pcl/features/from_meshes.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,15 +52,15 @@ namespace pcl
}


/** \brief Compute GICP-style covariance matrices given a point cloud and
/** \brief Compute GICP-style covariance matrices given a point cloud and
* the corresponding surface normals.
* \param[in] cloud Point cloud containing the XYZ coordinates,
* \param[in] normals Point cloud containing the corresponding surface normals.
* \param[out] covariances Vector of computed covariances.
* \param[in] Optional: Epsilon for the expected noise along the surface normal (default: 0.001)
*/
template <typename PointT, typename PointNT> inline void
computeApproximateCovariances(const pcl::PointCloud<PointT>& cloud,
computeApproximateCovariances(const pcl::PointCloud<PointT>& cloud,
const pcl::PointCloud<PointNT>& normals,
std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d> >& covariances,
double epsilon = 0.001)
Expand All @@ -72,9 +72,9 @@ namespace pcl
covariances.reserve (nr_points);
for (const auto& point: normals.points)
{
Eigen::Vector3d normal (normals.points[i].normal_x,
normals.points[i].normal_y,
normals.points[i].normal_z);
Eigen::Vector3d normal (point.normal_x,
point.normal_y,
point.normal_z);

// compute rotation matrix
Eigen::Matrix3d rot;
Expand All @@ -97,3 +97,6 @@ namespace pcl

}
}

#define PCL_INSTANTIATE_computeApproximateCovariances(T,NT) template PCL_EXPORTS void pcl::features::computeApproximateCovariances<T,NT> \
(const pcl::PointCloud<T>&, const pcl::PointCloud<NT>&, std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>>&, double);
50 changes: 50 additions & 0 deletions features/src/from_meshes.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*
* Software License Agreement (BSD License)
*
* Point Cloud Library (PCL) - www.pointclouds.org
* Copyright (c) 2010-2012, Willow Garage, Inc.
* Copyright (c) 2012-, Open Perception, Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder(s) nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*/

#include <pcl/features/from_meshes.h>

#ifndef PCL_NO_PRECOMPILE
#include <pcl/point_types.h>
#include <pcl/impl/instantiate.hpp>
// Instantiations of specific point types
#ifdef PCL_ONLY_CORE_POINT_TYPES
PCL_INSTANTIATE_PRODUCT(computeApproximateCovariances, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGBA))((pcl::Normal)))
#else
PCL_INSTANTIATE_PRODUCT(computeApproximateCovariances, (PCL_XYZ_POINT_TYPES)(PCL_NORMAL_POINT_TYPES))
#endif
#endif // PCL_NO_PRECOMPILE

0 comments on commit e6e7377

Please sign in to comment.