PageRenderTime 578ms CodeModel.GetById 37ms RepoModel.GetById 1ms app.codeStats 1ms

/features/include/pcl/features/ppf.h

https://bitbucket.org/ub216/cuda
C Header | 147 lines | 43 code | 14 blank | 90 comment | 0 complexity | 6d1d59bdcde43859493bfec56a8b68b6 MD5 | raw file
  1. /*
  2. * Software License Agreement (BSD License)
  3. *
  4. * Point Cloud Library (PCL) - www.pointclouds.org
  5. * Copyright (c) 2011, Alexandru-Eugen Ichim
  6. * Willow Garage, Inc
  7. * All rights reserved.
  8. *
  9. * Redistribution and use in source and binary forms, with or without
  10. * modification, are permitted provided that the following conditions
  11. * are met:
  12. *
  13. * * Redistributions of source code must retain the above copyright
  14. * notice, this list of conditions and the following disclaimer.
  15. * * Redistributions in binary form must reproduce the above
  16. * copyright notice, this list of conditions and the following
  17. * disclaimer in the documentation and/or other materials provided
  18. * with the distribution.
  19. * * Neither the name of Willow Garage, Inc. nor the names of its
  20. * contributors may be used to endorse or promote products derived
  21. * from this software without specific prior written permission.
  22. *
  23. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  24. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  25. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  26. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  27. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  28. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  29. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  30. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  31. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  32. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  33. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  34. * POSSIBILITY OF SUCH DAMAGE.
  35. *
  36. * $Id$
  37. */
  38. #ifndef PCL_PPF_H_
  39. #define PCL_PPF_H_
  40. #include <pcl/features/feature.h>
  41. #include <boost/unordered_map.hpp>
  42. namespace pcl
  43. {
  44. /** \brief
  45. * \param[in] p1
  46. * \param[in] n1
  47. * \param[in] p2
  48. * \param[in] n2
  49. * \param[out] f1
  50. * \param[out] f2
  51. * \param[out] f3
  52. * \param[out] f4
  53. */
  54. PCL_EXPORTS bool
  55. computePPFPairFeature (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1,
  56. const Eigen::Vector4f &p2, const Eigen::Vector4f &n2,
  57. float &f1, float &f2, float &f3, float &f4);
  58. /** \brief Class that calculates the "surflet" features for each pair in the given
  59. * pointcloud. Please refer to the following publication for more details:
  60. * B. Drost, M. Ulrich, N. Navab, S. Ilic
  61. * Model Globally, Match Locally: Efficient and Robust 3D Object Recognition
  62. * 2010 IEEE Conference on Computer Vision and Pattern Recognition (CVPR)
  63. * 13-18 June 2010, San Francisco, CA
  64. *
  65. * PointOutT is meant to be pcl::PPFSignature - contains the 4 values of the Surflet
  66. * feature and in addition, alpha_m for the respective pair - optimization proposed by
  67. * the authors (see above)
  68. *
  69. * \author Alexandru-Eugen Ichim
  70. */
  71. template <typename PointInT, typename PointNT, typename PointOutT>
  72. class PPFEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
  73. {
  74. public:
  75. using PCLBase<PointInT>::indices_;
  76. using Feature<PointInT, PointOutT>::input_;
  77. using Feature<PointInT, PointOutT>::feature_name_;
  78. using Feature<PointInT, PointOutT>::getClassName;
  79. using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
  80. typedef pcl::PointCloud<PointOutT> PointCloudOut;
  81. /** \brief Empty Constructor. */
  82. PPFEstimation ();
  83. private:
  84. /** \brief The method called for actually doing the computations
  85. * \param[out] output the resulting point cloud (which should be of type pcl::PPFSignature);
  86. * its size is the size of the input cloud, squared (i.e., one point for each pair in
  87. * the input cloud);
  88. */
  89. void
  90. computeFeature (PointCloudOut &output);
  91. /** \brief Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class
  92. * \param[out] output the output point cloud
  93. */
  94. void
  95. computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
  96. };
  97. /** \brief Class that calculates the "surflet" features for each pair in the given
  98. * pointcloud. Please refer to the following publication for more details:
  99. * B. Drost, M. Ulrich, N. Navab, S. Ilic
  100. * Model Globally, Match Locally: Efficient and Robust 3D Object Recognition
  101. * 2010 IEEE Conference on Computer Vision and Pattern Recognition (CVPR)
  102. * 13-18 June 2010, San Francisco, CA
  103. *
  104. * PointOutT is meant to be pcl::PPFSignature - contains the 4 values of the Surflet
  105. * feature and in addition, alpha_m for the respective pair - optimization proposed by
  106. * the authors (see above)
  107. *
  108. * \author Alexandru-Eugen Ichim
  109. */
  110. template <typename PointInT, typename PointNT>
  111. class PPFEstimation<PointInT, PointNT, Eigen::MatrixXf> : public PPFEstimation<PointInT, PointNT, pcl::PPFSignature>
  112. {
  113. public:
  114. using PPFEstimation<PointInT, PointNT, pcl::PPFSignature>::getClassName;
  115. using PPFEstimation<PointInT, PointNT, pcl::PPFSignature>::input_;
  116. using PPFEstimation<PointInT, PointNT, pcl::PPFSignature>::normals_;
  117. using PPFEstimation<PointInT, PointNT, pcl::PPFSignature>::indices_;
  118. private:
  119. /** \brief The method called for actually doing the computations
  120. * \param[out] output the resulting point cloud
  121. * its size is the size of the input cloud, squared (i.e., one point for each pair in
  122. * the input cloud);
  123. */
  124. void
  125. computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
  126. /** \brief Make the compute (&PointCloudOut); inaccessible from outside the class
  127. * \param[out] output the output point cloud
  128. */
  129. void
  130. compute (pcl::PointCloud<pcl::Normal> &) {}
  131. };
  132. }
  133. #endif // PCL_PPF_H_