Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef UTIL3D_REGISTRATION_H_
00029 #define UTIL3D_REGISTRATION_H_
00030
00031 #include <rtabmap/core/RtabmapExp.h>
00032
00033 #include <pcl/point_cloud.h>
00034 #include <pcl/point_types.h>
00035 #include <rtabmap/core/Transform.h>
00036 #include <opencv2/core/core.hpp>
00037
00038 namespace rtabmap
00039 {
00040
00041 namespace util3d
00042 {
00043
00044 int RTABMAP_EXP getCorrespondencesCount(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
00045 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
00046 float maxDistance);
00047
00048 Transform RTABMAP_EXP transformFromXYZCorrespondencesSVD(
00049 const pcl::PointCloud<pcl::PointXYZ> & cloud1,
00050 const pcl::PointCloud<pcl::PointXYZ> & cloud2);
00051
00052 Transform RTABMAP_EXP transformFromXYZCorrespondences(
00053 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud1,
00054 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud2,
00055 double inlierThreshold = 0.02,
00056 int iterations = 100,
00057 int refineModelIterations = 10,
00058 double refineModelSigma = 3.0,
00059 std::vector<int> * inliers = 0,
00060 cv::Mat * variance = 0);
00061
00062 void RTABMAP_EXP computeVarianceAndCorrespondences(
00063 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudA,
00064 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudB,
00065 double maxCorrespondenceDistance,
00066 double maxCorrespondenceAngle,
00067 double & variance,
00068 int & correspondencesOut);
00069 void RTABMAP_EXP computeVarianceAndCorrespondences(
00070 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudA,
00071 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
00072 double maxCorrespondenceDistance,
00073 double & variance,
00074 int & correspondencesOut);
00075
00076 Transform RTABMAP_EXP icp(
00077 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
00078 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
00079 double maxCorrespondenceDistance,
00080 int maximumIterations,
00081 bool & hasConverged,
00082 pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
00083 float epsilon = 0.0f,
00084 bool icp2D = false);
00085
00086 Transform RTABMAP_EXP icpPointToPlane(
00087 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
00088 const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
00089 double maxCorrespondenceDistance,
00090 int maximumIterations,
00091 bool & hasConverged,
00092 pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
00093 float epsilon = 0.0f,
00094 bool icp2D = false);
00095
00096 }
00097 }
00098
00099 #endif