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::PointXYZ>::ConstPtr & cloudA,
71 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
72 double maxCorrespondenceDistance,
74 int & correspondencesOut);
77 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
78 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
79 double maxCorrespondenceDistance,
80 int maximumIterations,
82 pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
87 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
88 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
89 double maxCorrespondenceDistance,
90 int maximumIterations,
92 pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
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)