28 #ifndef UTIL3D_REGISTRATION_H_ 29 #define UTIL3D_REGISTRATION_H_ 33 #include <pcl/point_cloud.h> 34 #include <pcl/point_types.h> 36 #include <opencv2/core/core.hpp> 45 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
49 const pcl::PointCloud<pcl::PointXYZ> & cloud1,
50 const pcl::PointCloud<pcl::PointXYZ> & cloud2);
53 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud1,
54 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud2,
55 double inlierThreshold = 0.02,
57 int refineModelIterations = 10,
58 double refineModelSigma = 3.0,
59 std::vector<int> * inliers = 0,
60 cv::Mat * variance = 0);
63 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudA,
64 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudB,
65 double maxCorrespondenceDistance,
66 double maxCorrespondenceAngle,
68 int & correspondencesOut);
70 const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloudA,
71 const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloudB,
72 double maxCorrespondenceDistance,
73 double maxCorrespondenceAngle,
75 int & correspondencesOut);
77 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudA,
78 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
79 double maxCorrespondenceDistance,
81 int & correspondencesOut);
83 const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloudA,
84 const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloudB,
85 double maxCorrespondenceDistance,
87 int & correspondencesOut);
90 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
91 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
92 double maxCorrespondenceDistance,
93 int maximumIterations,
95 pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
99 const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloud_source,
100 const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloud_target,
101 double maxCorrespondenceDistance,
102 int maximumIterations,
104 pcl::PointCloud<pcl::PointXYZI> & cloud_source_registered,
105 float epsilon = 0.0f,
109 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
110 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
111 double maxCorrespondenceDistance,
112 int maximumIterations,
114 pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
115 float epsilon = 0.0f,
118 const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloud_source,
119 const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloud_target,
120 double maxCorrespondenceDistance,
121 int maximumIterations,
123 pcl::PointCloud<pcl::PointXYZINormal> & cloud_source_registered,
124 float epsilon = 0.0f,
Transform RTABMAP_EXP transformFromXYZCorrespondencesSVD(const pcl::PointCloud< pcl::PointXYZ > &cloud1, const pcl::PointCloud< pcl::PointXYZ > &cloud2)
Transform RTABMAP_EXP 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)
void RTABMAP_EXP computeVarianceAndCorrespondences(const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudA, const pcl::PointCloud< pcl::PointNormal >::ConstPtr &cloudB, double maxCorrespondenceDistance, double maxCorrespondenceAngle, double &variance, int &correspondencesOut)
Transform RTABMAP_EXP 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)
Transform RTABMAP_EXP 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)
int RTABMAP_EXP getCorrespondencesCount(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, float maxDistance)