Point Cloud Library (PCL)  1.14.1-dev
geometric_consistency.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, Willow Garage, Inc.
6  *
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  */
39 
40 #pragma once
41 
42 #include <pcl/recognition/cg/correspondence_grouping.h>
43 #include <pcl/point_cloud.h>
44 
45 namespace pcl
46 {
47 
48  /** \brief Class implementing a 3D correspondence grouping enforcing geometric consistency among feature correspondences
49  *
50  * \author Federico Tombari, Tommaso Cavallari, Aitor Aldoma
51  * \ingroup recognition
52  */
53  template<typename PointModelT, typename PointSceneT>
54  class GeometricConsistencyGrouping : public CorrespondenceGrouping<PointModelT, PointSceneT>
55  {
56  public:
58  using PointCloudPtr = typename PointCloud::Ptr;
60 
62 
63  /** \brief Constructor */
65 
66  /** \brief Sets the minimum cluster size
67  * \param[in] threshold the minimum cluster size
68  */
69  inline void
70  setGCThreshold (int threshold)
71  {
72  gc_threshold_ = threshold;
73  }
74 
75  /** \brief Gets the minimum cluster size.
76  *
77  * \return the minimum cluster size used by GC.
78  */
79  inline int
80  getGCThreshold () const
81  {
82  return (gc_threshold_);
83  }
84 
85  /** \brief Sets the consensus set resolution. This should be in metric units.
86  *
87  * \param[in] gc_size consensus set resolution.
88  */
89  inline void
90  setGCSize (double gc_size)
91  {
92  gc_size_ = gc_size;
93  }
94 
95  /** \brief Gets the consensus set resolution.
96  *
97  * \return the consensus set resolution.
98  */
99  inline double
100  getGCSize () const
101  {
102  return (gc_size_);
103  }
104 
105  /** \brief The main function, recognizes instances of the model into the scene set by the user.
106  *
107  * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene.
108  *
109  * \return true if the recognition had been successful or false if errors have occurred.
110  */
111  bool
112  recognize (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > &transformations);
113 
114  /** \brief The main function, recognizes instances of the model into the scene set by the user.
115  *
116  * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene.
117  * \param[out] clustered_corrs a vector containing the correspondences for each instance of the model found within the input data (the same output of clusterCorrespondences).
118  *
119  * \return true if the recognition had been successful or false if errors have occurred.
120  */
121  bool
122  recognize (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > &transformations, std::vector<pcl::Correspondences> &clustered_corrs);
123 
124  protected:
128 
129  /** \brief Minimum cluster size. It shouldn't be less than 3, since at least 3 correspondences are needed to compute the 6DOF pose */
131 
132  /** \brief Resolution of the consensus set used to cluster correspondences together*/
133  double gc_size_{1.0};
134 
135  /** \brief Transformations found by clusterCorrespondences method. */
136  std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > found_transformations_;
137 
138  /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene.
139  *
140  * \param[out] model_instances a vector containing the clustered correspondences for each model found on the scene.
141  * \return true if the clustering had been successful or false if errors have occurred.
142  */
143  void
144  clusterCorrespondences (std::vector<Correspondences> &model_instances) override;
145  };
146 }
147 
148 #ifdef PCL_NO_PRECOMPILE
149 #include <pcl/recognition/impl/cg/geometric_consistency.hpp>
150 #endif
Abstract base class for Correspondence Grouping algorithms.
typename SceneCloud::ConstPtr SceneCloudConstPtr
Class implementing a 3D correspondence grouping enforcing geometric consistency among feature corresp...
int gc_threshold_
Minimum cluster size.
typename PointCloud::ConstPtr PointCloudConstPtr
int getGCThreshold() const
Gets the minimum cluster size.
void setGCThreshold(int threshold)
Sets the minimum cluster size.
void setGCSize(double gc_size)
Sets the consensus set resolution.
double gc_size_
Resolution of the consensus set used to cluster correspondences together.
void clusterCorrespondences(std::vector< Correspondences > &model_instances) override
Cluster the input correspondences in order to distinguish between different instances of the model in...
typename PointCloud::Ptr PointCloudPtr
GeometricConsistencyGrouping()=default
Constructor.
bool recognize(std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transformations)
The main function, recognizes instances of the model into the scene set by the user.
std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > found_transformations_
Transformations found by clusterCorrespondences method.
double getGCSize() const
Gets the consensus set resolution.
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414