util3d_registration.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef UTIL3D_REGISTRATION_H_
29 #define UTIL3D_REGISTRATION_H_
30 
31 #include <rtabmap/core/rtabmap_core_export.h>
32 
33 #include <pcl/point_cloud.h>
34 #include <pcl/point_types.h>
35 #include <rtabmap/core/Transform.h>
36 #include <opencv2/core/core.hpp>
37 
38 namespace rtabmap
39 {
40 
41 namespace util3d
42 {
43 
44 int RTABMAP_CORE_EXPORT getCorrespondencesCount(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
45  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
46  float maxDistance);
47 
48 Transform RTABMAP_CORE_EXPORT transformFromXYZCorrespondencesSVD(
49  const pcl::PointCloud<pcl::PointXYZ> & cloud1,
50  const pcl::PointCloud<pcl::PointXYZ> & cloud2);
51 
52 Transform RTABMAP_CORE_EXPORT transformFromXYZCorrespondences(
53  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud1,
54  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud2,
55  double inlierThreshold = 0.02,
56  int iterations = 100,
57  int refineModelIterations = 10,
58  double refineModelSigma = 3.0,
59  std::vector<int> * inliers = 0,
60  cv::Mat * variance = 0);
61 
62 void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
63  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudA,
64  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudB,
65  double maxCorrespondenceDistance,
66  double maxCorrespondenceAngle, // <=0 means that we don't care about normal angle difference
67  double & variance,
68  int & correspondencesOut,
69  bool reciprocal);
70 void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
71  const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloudA,
72  const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloudB,
73  double maxCorrespondenceDistance,
74  double maxCorrespondenceAngle, // <=0 means that we don't care about normal angle difference
75  double & variance,
76  int & correspondencesOut,
77  bool reciprocal);
78 void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
79  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudA,
80  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
81  double maxCorrespondenceDistance,
82  double & variance,
83  int & correspondencesOut,
84  bool reciprocal);
85 void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
86  const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloudA,
87  const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloudB,
88  double maxCorrespondenceDistance,
89  double & variance,
90  int & correspondencesOut,
91  bool reciprocal);
92 
93 Transform RTABMAP_CORE_EXPORT icp(
94  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
95  const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
96  double maxCorrespondenceDistance,
97  int maximumIterations,
98  bool & hasConverged,
99  pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
100  float epsilon = 0.0f,
101  bool icp2D = false);
102 Transform RTABMAP_CORE_EXPORT icp(
103  const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloud_source,
104  const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloud_target,
105  double maxCorrespondenceDistance,
106  int maximumIterations,
107  bool & hasConverged,
108  pcl::PointCloud<pcl::PointXYZI> & cloud_source_registered,
109  float epsilon = 0.0f,
110  bool icp2D = false);
111 
112 Transform RTABMAP_CORE_EXPORT icpPointToPlane(
113  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
114  const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
115  double maxCorrespondenceDistance,
116  int maximumIterations,
117  bool & hasConverged,
118  pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
119  float epsilon = 0.0f,
120  bool icp2D = false);
121 Transform RTABMAP_CORE_EXPORT icpPointToPlane(
122  const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloud_source,
123  const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloud_target,
124  double maxCorrespondenceDistance,
125  int maximumIterations,
126  bool & hasConverged,
127  pcl::PointCloud<pcl::PointXYZINormal> & cloud_source_registered,
128  float epsilon = 0.0f,
129  bool icp2D = false);
130 
131 } // namespace util3d
132 } // namespace rtabmap
133 
134 #endif /* UTIL3D_REGISTRATION_H_ */
rtabmap::util3d::transformFromXYZCorrespondences
Transform RTABMAP_CORE_EXPORT transformFromXYZCorrespondences(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud1, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud2, double inlierThreshold=0.02, int iterations=100, int refineModelIterations=10, double refineModelSigma=3.0, std::vector< int > *inliers=0, cv::Mat *variance=0)
Definition: util3d_registration.cpp:63
Transform.h
rtabmap::util3d::computeVarianceAndCorrespondences
void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudB, double maxCorrespondenceDistance, double maxCorrespondenceAngle, double &variance, int &correspondencesOut, bool reciprocal)
Definition: util3d_registration.cpp:303
rtabmap::util3d::icp
Transform RTABMAP_CORE_EXPORT icp(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointXYZ > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false)
Definition: util3d_registration.cpp:424
rtabmap::util3d::icpPointToPlane
Transform RTABMAP_CORE_EXPORT icpPointToPlane(const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointNormal > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false)
Definition: util3d_registration.cpp:495
rtabmap::util3d::getCorrespondencesCount
int RTABMAP_CORE_EXPORT getCorrespondencesCount(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, float maxDistance)
Definition: util3d_correspondences.cpp:276
epsilon
double epsilon
rtabmap::util3d::transformFromXYZCorrespondencesSVD
Transform RTABMAP_CORE_EXPORT transformFromXYZCorrespondencesSVD(const pcl::PointCloud< pcl::PointXYZ > &cloud1, const pcl::PointCloud< pcl::PointXYZ > &cloud2)
Definition: util3d_registration.cpp:50
rtabmap
Definition: CameraARCore.cpp:35


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:41