28 #ifndef CORELIB_SRC_ICP_CCCORELIB_H_ 29 #define CORELIB_SRC_ICP_CCCORELIB_H_ 31 #include <CCCoreLib/RegistrationTools.h> 36 const pcl::PointCloud<pcl::PointXYZI>::Ptr & fromCloud,
37 pcl::PointCloud<pcl::PointXYZI>::Ptr & toCloud,
38 int maxIterations = 150,
39 double minRMSDecrease = 0.00001,
40 bool force3DoF =
false,
41 bool force4DoF =
false,
42 int samplingLimit = 50000,
43 double finalOverlapRatio = 0.85,
44 bool filterOutFarthestPoints =
false,
45 double maxFinalRMS = 0.2,
47 std::string * errorMsg = 0)
49 UDEBUG(
"maxIterations=%d", maxIterations);
50 UDEBUG(
"minRMSDecrease=%f", minRMSDecrease);
51 UDEBUG(
"samplingLimit=%d", samplingLimit);
52 UDEBUG(
"finalOverlapRatio=%f", finalOverlapRatio);
53 UDEBUG(
"filterOutFarthestPoints=%s", filterOutFarthestPoints?
"true":
"false");
54 UDEBUG(
"force 3DoF=%s 4DoF=%s", force3DoF?
"true":
"false", force4DoF?
"true":
"false");
55 UDEBUG(
"maxFinalRMS=%f", maxFinalRMS);
59 CCCoreLib::ICPRegistrationTools::RESULT_TYPE result;
60 CCCoreLib::PointProjectionTools::Transformation transform;
61 CCCoreLib::ICPRegistrationTools::Parameters
params;
63 if(minRMSDecrease > 0.0)
65 params.convType = CCCoreLib::ICPRegistrationTools::MAX_ERROR_CONVERGENCE;
66 params.minRMSDecrease = minRMSDecrease;
70 params.convType = CCCoreLib::ICPRegistrationTools::MAX_ITER_CONVERGENCE;
71 params.nbMaxIterations = maxIterations;
73 params.adjustScale =
false;
74 params.filterOutFarthestPoints = filterOutFarthestPoints;
75 params.samplingLimit = samplingLimit;
76 params.finalOverlapRatio = finalOverlapRatio;
77 params.modelWeights =
nullptr;
78 params.dataWeights =
nullptr;
79 params.transformationFilters = force3DoF?33:force4DoF?1:0;
80 params.maxThreadCount = 0;
83 double finalError = 0.0;
84 unsigned finalPointCount = 0;
86 CCCoreLib::PointCloud toPointCloud = CCCoreLib::PointCloud();
87 CCCoreLib::PointCloud fromPointCloud = CCCoreLib::PointCloud();
89 fromPointCloud.reserve(fromCloud->points.size());
90 for(
uint nIndex=0; nIndex < fromCloud->points.size(); nIndex++)
93 P.x = fromCloud->points[nIndex].x;
94 P.y = fromCloud->points[nIndex].y;
95 P.z = force3DoF?0:fromCloud->points[nIndex].z;
96 fromPointCloud.addPoint(P);
98 toPointCloud.reserve(toCloud->points.size());
99 for(
uint nIndex=0; nIndex < toCloud->points.size(); nIndex++)
102 P.x = toCloud->points[nIndex].x;
103 P.y = toCloud->points[nIndex].y;
104 P.z = force3DoF?0:toCloud->points[nIndex].z;
105 toPointCloud.addPoint(P);
108 UDEBUG(
"CCCoreLib: start ICP");
109 result = CCCoreLib::ICPRegistrationTools::Register(
117 UDEBUG(
"CCCoreLib: ICP done!");
119 UDEBUG(
"CC ICP result: %d", result);
120 UDEBUG(
"CC Final error: %f . Finall Pointcount: %d", finalError, finalPointCount);
121 UDEBUG(
"CC ICP success Trans: %f %f %f", transform.T.x,transform.T.y,transform.T.z);
125 *finalRMS = (float)finalError;
130 std::string msg =
uFormat(
"CCCoreLib has failed: Rejecting transform as result %d !=1", result);
138 return icpTransformation;
140 else if(!transform.R.isValid())
142 std::string msg =
uFormat(
"CCCoreLib has failed: Rotation matrix is invalid");
149 return icpTransformation;
152 Eigen::Matrix4f matrix;
158 matrix(i,j)=transform.R.getValue(i,j);
163 matrix(i,3)=transform.T[i];
167 icpTransformation = icpTransformation.
inverse();
170 if(finalError > maxFinalRMS)
172 std::string msg =
uFormat(
"CCCoreLib has failed: Rejecting transform as RMS %f > %f (%s) ", finalError, maxFinalRMS, rtabmap::Parameters::kIcpCCMaxFinalRMS().c_str());
180 return icpTransformation;
rtabmap::Transform icpCC(const pcl::PointCloud< pcl::PointXYZI >::Ptr &fromCloud, pcl::PointCloud< pcl::PointXYZI >::Ptr &toCloud, int maxIterations=150, double minRMSDecrease=0.00001, bool force3DoF=false, bool force4DoF=false, int samplingLimit=50000, double finalOverlapRatio=0.85, bool filterOutFarthestPoints=false, double maxFinalRMS=0.2, float *finalRMS=0, std::string *errorMsg=0)
std::string UTILITE_EXP uFormat(const char *fmt,...)