Point Cloud Library (PCL) 1.13.1
Loading...
Searching...
No Matches
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
45namespace 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:
60
62
63 /** \brief Constructor */
68
69
70 /** \brief Sets the minimum cluster size
71 * \param[in] threshold the minimum cluster size
72 */
73 inline void
74 setGCThreshold (int threshold)
75 {
76 gc_threshold_ = threshold;
77 }
78
79 /** \brief Gets the minimum cluster size.
80 *
81 * \return the minimum cluster size used by GC.
82 */
83 inline int
85 {
86 return (gc_threshold_);
87 }
88
89 /** \brief Sets the consensus set resolution. This should be in metric units.
90 *
91 * \param[in] gc_size consensus set resolution.
92 */
93 inline void
94 setGCSize (double gc_size)
95 {
96 gc_size_ = gc_size;
97 }
98
99 /** \brief Gets the consensus set resolution.
100 *
101 * \return the consensus set resolution.
102 */
103 inline double
104 getGCSize () const
105 {
106 return (gc_size_);
107 }
108
109 /** \brief The main function, recognizes instances of the model into the scene set by the user.
110 *
111 * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene.
112 *
113 * \return true if the recognition had been successful or false if errors have occurred.
114 */
115 bool
116 recognize (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > &transformations);
117
118 /** \brief The main function, recognizes instances of the model into the scene set by the user.
119 *
120 * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene.
121 * \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).
122 *
123 * \return true if the recognition had been successful or false if errors have occurred.
124 */
125 bool
126 recognize (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > &transformations, std::vector<pcl::Correspondences> &clustered_corrs);
127
128 protected:
129 using CorrespondenceGrouping<PointModelT, PointSceneT>::input_;
130 using CorrespondenceGrouping<PointModelT, PointSceneT>::scene_;
131 using CorrespondenceGrouping<PointModelT, PointSceneT>::model_scene_corrs_;
132
133 /** \brief Minimum cluster size. It shouldn't be less than 3, since at least 3 correspondences are needed to compute the 6DOF pose */
135
136 /** \brief Resolution of the consensus set used to cluster correspondences together*/
137 double gc_size_;
138
139 /** \brief Transformations found by clusterCorrespondences method. */
140 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > found_transformations_;
141
142 /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene.
143 *
144 * \param[out] model_instances a vector containing the clustered correspondences for each model found on the scene.
145 * \return true if the clustering had been successful or false if errors have occurred.
146 */
147 void
148 clusterCorrespondences (std::vector<Correspondences> &model_instances) override;
149 };
150}
151
152#ifdef PCL_NO_PRECOMPILE
153#include <pcl/recognition/impl/cg/geometric_consistency.hpp>
154#endif
Abstract base class for Correspondence Grouping algorithms.
CorrespondencesConstPtr model_scene_corrs_
The correspondences between points in the input and the scene datasets.
SceneCloudConstPtr scene_
The scene cloud.
typename SceneCloud::ConstPtr SceneCloudConstPtr
Class implementing a 3D correspondence grouping enforcing geometric consistency among feature corresp...
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...
pcl::PointCloud< PointModelT > PointCloud
typename pcl::CorrespondenceGrouping< PointModelT, PointSceneT >::SceneCloudConstPtr SceneCloudConstPtr
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.
PointCloudConstPtr input_
The input point cloud dataset.
Definition pcl_base.h:147
PointCloud represents the base class in PCL for storing collections of 3D points.
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr