26 #include <Eigen/Dense> 47 if (outInfo) tictac.Tic();
49 switch (options.ICP_algorithm)
53 ICP_Method_Classic(m1, mm2, initialEstimationPDF, outInfoVal);
57 ICP_Method_LM(m1, mm2, initialEstimationPDF, outInfoVal);
61 "Invalid value for ICP_algorithm: %i",
62 static_cast<int>(options.ICP_algorithm));
69 if (
auto* o = dynamic_cast<TReturnInfo*>(&outInfo.value().get()); o)
88 section,
"ICP_algorithm", ICP_algorithm);
90 section,
"ICP_covariance_method", ICP_covariance_method);
94 section.c_str(),
"thresholdAng_DEG",
RAD2DEG(thresholdAng)));
111 section.c_str(),
"ransac_fuseMaxDiffPhi_DEG",
112 RAD2DEG(ransac_fuseMaxDiffPhi)));
123 corresponding_points_decimation,
int,
iniFile, section);
130 ICP_algorithm,
"The ICP algorithm to use (see enum TICPAlgorithm)");
132 ICP_covariance_method,
133 "Method to use for covariance estimation (see enum " 134 "TICPCovarianceMethod)");
137 "Only the closest correspondence for each reference point will be " 144 "Initial threshold distance for two points to be a match");
147 "Initial threshold distance for two points to be a match");
150 "The scale factor for thresholds every time convergence is achieved");
152 smallestThresholdDist,
153 "The size for threshold such that iterations will stop, " 154 "since it is considered precise enough.");
176 return options.use_kernel ? (x2 / (x2 + rho2)) : x2;
195 size_t nCorrespondences = 0;
196 bool keepApproaching;
206 ASSERT_(options.ALFA >= 0 && options.ALFA < 1);
216 gaussPdf = std::make_shared<CPosePDFGaussian>();
219 gaussPdf->mean = grossEst;
226 options.thresholdDist;
228 options.thresholdAng;
233 options.corresponding_points_decimation;
250 gaussPdf->mean.x(), gaussPdf->mean.y(),
256 correspondences, matchParams, matchExtraResults);
258 nCorrespondences = correspondences.size();
263 if (!nCorrespondences)
266 keepApproaching =
false;
280 keepApproaching =
true;
281 if (!(fabs(lastMeanPose.
x() - gaussPdf->mean.x()) >
282 options.minAbsStep_trans ||
283 fabs(lastMeanPose.
y() - gaussPdf->mean.y()) >
284 options.minAbsStep_trans ||
286 lastMeanPose.
phi() - gaussPdf->mean.phi())) >
287 options.minAbsStep_rot))
292 options.smallestThresholdDist)
293 keepApproaching =
false;
296 options.corresponding_points_decimation)
300 lastMeanPose = gaussPdf->mean;
307 if (outInfo.
nIterations >= options.maxIterations &&
309 options.smallestThresholdDist)
315 (keepApproaching && outInfo.
nIterations < options.maxIterations) ||
318 options.smallestThresholdDist));
323 if (!options.skip_cov_calculation && nCorrespondences)
325 switch (options.ICP_covariance_method)
333 gaussPdf->cov *= options.covariance_varPoints;
346 const TPose2D transf = gaussPdf->mean.asTPose();
348 double ccos = cos(transf.
phi);
349 double csin = sin(transf.
phi);
357 double rho2 =
square(options.kernel_rho);
358 mrpt::tfest::TMatchingPairList::iterator it;
360 for (i = 0, it = correspondences.begin();
361 i < nCorrespondences; ++i, ++it)
363 float other_x_trans =
364 transf.
x + ccos * it->other_x - csin * it->other_y;
365 float other_y_trans =
366 transf.
y + csin * it->other_x + ccos * it->other_y;
370 w1 = other_x_trans - Axy;
373 square(it->this_y - other_y_trans),
379 square(it->this_y - other_y_trans),
382 w3 = other_x_trans + Axy;
385 square(it->this_y - other_y_trans),
389 A = ((q3 - q2) / ((w3 - w2) * (w3 - w1))) -
390 ((q1 - q2) / ((w1 - w2) * (w3 - w1)));
391 B = ((q1 - q2) + (
A * ((w2 * w2) - (w1 * w1)))) /
394 D(0, i) = (2 *
A * other_x_trans) + B;
398 w1 = other_y_trans - Axy;
400 square(it->this_x - other_x_trans) +
406 square(it->this_x - other_x_trans) +
410 w3 = other_y_trans + Axy;
412 square(it->this_x - other_x_trans) +
417 A = ((q3 - q2) / ((w3 - w2) * (w3 - w1))) -
418 ((q1 - q2) / ((w1 - w2) * (w3 - w1)));
419 B = ((q1 - q2) + (
A * ((w2 * w2) - (w1 * w1)))) /
422 D(1, i) = (2 *
A * other_y_trans) + B;
428 (-csin * it->other_x - ccos * it->other_y) +
429 D(1, i) * (ccos * it->other_x - csin * it->other_y);
437 for (i = 0; i < 3; i++)
447 "Invalid value for ICP_covariance_method: %i",
448 static_cast<int>(options.ICP_covariance_method));
454 if (!nCorrespondences || options.skip_quality_calculation)
476 TPoint3D(gaussPdf->mean.x(), gaussPdf->mean.y(), 0);
480 correspondences, matchParams, matchExtraResults);
486 correspondences, matchParams, matchExtraResults);
492 correspondences, matchParams, matchExtraResults);
498 correspondences, matchParams, matchExtraResults);
503 correspondences, matchParams, matchExtraResults);
507 -max(EX1 - E0, max(EX2 - E0, max(EY1 - E0, EY2 - E0))) /
517 if (options.doRANSAC)
520 params.ransac_minSetSize = options.ransac_minSetSize;
521 params.ransac_maxSetSize = options.ransac_maxSetSize;
522 params.ransac_mahalanobisDistanceThreshold =
523 options.ransac_mahalanobisDistanceThreshold;
524 params.ransac_nSimulations = options.ransac_nSimulations;
525 params.ransac_fuseByCorrsMatch = options.ransac_fuseByCorrsMatch;
526 params.ransac_fuseMaxDiffXY = options.ransac_fuseMaxDiffXY;
527 params.ransac_fuseMaxDiffPhi = options.ransac_fuseMaxDiffPhi;
528 params.ransac_algorithmForLandmarks =
false;
534 SOG = std::make_shared<CPosePDFSOG>();
543 resultPDF = gaussPdf;
563 size_t nCorrespondences = 0;
564 bool keepIteratingICP;
568 std::vector<float> other_xs_trans, other_ys_trans;
575 const bool onlyUniqueRobust = options.onlyUniqueRobust;
579 const auto* m1 =
dynamic_cast<const CPointsMap*
>(mm1);
583 ASSERT_(options.ALFA > 0 && options.ALFA < 1);
594 options.thresholdDist;
596 options.thresholdAng;
602 options.corresponding_points_decimation;
627 m1->determineMatching2D(
630 correspondences, matchParams, matchExtraResults);
632 nCorrespondences = correspondences.size();
634 if (!nCorrespondences)
637 keepIteratingICP =
false;
644 dJ_dq.
setSize(3, nCorrespondences);
648 double lambda = options.LM_initial_lambda;
650 double ccos = cos(q.
phi());
651 double csin = sin(q.
phi());
657 options.Axy_aprox_derivatives;
662 std::vector<float> sq_errors;
664 q, sq_errors, other_xs_trans, other_ys_trans);
665 double OSE_initial =
math::sum(sq_errors);
669 double rho2 =
square(options.kernel_rho);
670 mrpt::tfest::TMatchingPairList::iterator it;
671 std::vector<float>::const_iterator other_x_trans, other_y_trans;
674 for (i = 0, it = correspondences.begin(),
675 other_x_trans = other_xs_trans.begin(),
676 other_y_trans = other_ys_trans.begin();
677 i < nCorrespondences;
678 ++i, ++it, ++other_x_trans, ++other_y_trans)
684 #ifndef ICP_DISTANCES_TO_LINE 685 w1 = *other_x_trans - Axy;
686 q1 = m1->squareDistanceToClosestCorrespondence(
688 q1 = kernel(q1, rho2);
691 q2 = m1->squareDistanceToClosestCorrespondence(
693 q2 = kernel(q2, rho2);
695 w3 = *other_x_trans + Axy;
696 q3 = m1->squareDistanceToClosestCorrespondence(
698 q3 = kernel(q3, rho2);
702 float x1, y1, x2, y2, d1, d2;
703 m1->kdTreeTwoClosestPoint2D(
704 *other_x_trans, *other_y_trans,
709 w1 = *other_x_trans - Axy;
711 w1, *other_y_trans, x1, y1, x2, y2);
712 q1 = kernel(q1, rho2);
716 w2, *other_y_trans, x1, y1, x2, y2);
717 q2 = kernel(q2, rho2);
719 w3 = *other_x_trans + Axy;
721 w3, *other_y_trans, x1, y1, x2, y2);
722 q3 = kernel(q3, rho2);
725 A = ((q3 - q2) / ((w3 - w2) * (w3 - w1))) -
726 ((q1 - q2) / ((w1 - w2) * (w3 - w1)));
727 B = ((q1 - q2) + (
A * ((w2 * w2) - (w1 * w1)))) / (w1 - w2);
729 dJ_dq(0, i) = (2 *
A * *other_x_trans) + B;
733 w1 = *other_y_trans - Axy;
734 #ifdef ICP_DISTANCES_TO_LINE 736 *other_x_trans, w1, x1, y1, x2, y2);
737 q1 = kernel(q1, rho2);
740 square(it->this_x - *other_x_trans) +
752 w3 = *other_y_trans + Axy;
753 #ifdef ICP_DISTANCES_TO_LINE 755 *other_x_trans, w3, x1, y1, x2, y2);
756 q3 = kernel(q3, rho2);
759 square(it->this_x - *other_x_trans) +
765 A = ((q3 - q2) / ((w3 - w2) * (w3 - w1))) -
766 ((q1 - q2) / ((w1 - w2) * (w3 - w1)));
767 B = ((q1 - q2) + (
A * ((w2 * w2) - (w1 * w1)))) / (w1 - w2);
769 dJ_dq(1, i) = (2 *
A * *other_y_trans) + B;
775 (-csin * it->other_x - ccos * it->other_y) +
776 dJ_dq(1, i) * (ccos * it->other_x - csin * it->other_y);
789 bool keepIteratingLM =
true;
796 std::vector<float> new_sq_errors, new_other_xs_trans,
799 const size_t maxLMiters = 100;
801 while (keepIteratingLM && ++nLMiters < maxLMiters)
807 for (i = 0; i < 3; i++)
814 const Eigen::Vector3f LM_delta =
817 &sq_errors[0], sq_errors.size()))
820 q_new.
x(q.
x() - LM_delta[0]);
821 q_new.
y(q.
y() - LM_delta[1]);
822 q_new.
phi(q.
phi() - LM_delta[2]);
827 q_new, new_sq_errors, new_other_xs_trans,
830 float OSE_new =
math::sum(new_sq_errors);
832 bool improved = OSE_new < OSE_initial;
835 cout <<
"_____________" << endl;
836 cout <<
"q -> q_new : " << q <<
" -> " << q_new << endl;
837 printf(
"err: %f -> %f lambda: %e\n", OSE_initial ,OSE_new, lambda );
843 fabs(LM_delta[0]) > options.minAbsStep_trans ||
844 fabs(LM_delta[1]) > options.minAbsStep_trans ||
845 fabs(LM_delta[2]) > options.minAbsStep_rot;
853 OSE_initial = OSE_new;
864 cout <<
"ICP loop: " << lastMeanPose <<
" -> " << q <<
" LM iters: " << nLMiters <<
" threshold: " << matchParams.
maxDistForCorrespondence << endl;
869 keepIteratingICP =
true;
870 if (fabs(lastMeanPose.
x() - q.
x()) < options.minAbsStep_trans &&
871 fabs(lastMeanPose.
y() - q.
y()) < options.minAbsStep_trans &&
873 options.minAbsStep_rot)
878 options.smallestThresholdDist)
879 keepIteratingICP =
false;
882 options.corresponding_points_decimation)
891 if (outInfo.
nIterations >= options.maxIterations &&
893 options.smallestThresholdDist)
899 (keepIteratingICP && outInfo.
nIterations < options.maxIterations) ||
902 options.smallestThresholdDist));
913 return CPosePDFGaussian::Create(q, C_inv.
cast_double());
928 if (outInfo) tictac.Tic();
930 switch (options.ICP_algorithm)
934 ICP3D_Method_Classic(m1, mm2, initialEstimationPDF, outInfoVal);
941 "Invalid value for ICP_algorithm: %i",
942 static_cast<int>(options.ICP_algorithm));
949 if (
auto* o = dynamic_cast<TReturnInfo*>(&outInfo.value().get()); o)
967 size_t nCorrespondences = 0;
968 bool keepApproaching;
979 ASSERT_(options.ALFA > 0 && options.ALFA < 1);
989 gaussPdf = std::make_shared<CPose3DPDFGaussian>();
992 gaussPdf->mean = grossEst;
999 options.thresholdDist;
1001 options.thresholdAng;
1005 options.corresponding_points_decimation;
1019 gaussPdf->mean.x(), gaussPdf->mean.y(), gaussPdf->mean.z());
1027 correspondences, matchParams, matchExtraResults);
1029 nCorrespondences = correspondences.size();
1031 if (!nCorrespondences)
1034 keepApproaching =
false;
1041 double transf_scale;
1043 correspondences, estPoseQuat, transf_scale,
1049 keepApproaching =
true;
1050 if (!(fabs(lastMeanPose.
x() - gaussPdf->mean.x()) >
1051 options.minAbsStep_trans ||
1052 fabs(lastMeanPose.
y() - gaussPdf->mean.y()) >
1053 options.minAbsStep_trans ||
1054 fabs(lastMeanPose.z() - gaussPdf->mean.z()) >
1055 options.minAbsStep_trans ||
1057 lastMeanPose.
yaw() - gaussPdf->mean.yaw())) >
1058 options.minAbsStep_rot ||
1060 lastMeanPose.
pitch() - gaussPdf->mean.pitch())) >
1061 options.minAbsStep_rot ||
1063 lastMeanPose.
roll() - gaussPdf->mean.roll())) >
1064 options.minAbsStep_rot))
1069 options.smallestThresholdDist)
1070 keepApproaching =
false;
1073 options.corresponding_points_decimation)
1077 lastMeanPose = gaussPdf->mean;
1084 if (outInfo.
nIterations >= options.maxIterations &&
1086 options.smallestThresholdDist)
1092 (keepApproaching && outInfo.
nIterations < options.maxIterations) ||
1095 options.smallestThresholdDist));
1100 if (!options.skip_cov_calculation && nCorrespondences)
1111 resultPDF = gaussPdf;
std::ostream & operator<<(std::ostream &o, const TFTDIDevice &d)
Print out all the information of a FTDI device in textual form.
Use the covariance of the optimal registration, disregarding uncertainty in data association.
mrpt::math::TPoint3D angularDistPivotPoint
The point used to calculate angular distances: e.g.
float maxAngularDistForCorrespondence
Allowed "angular error" (in radians): this permits larger pairing threshold distances to more distant...
CPose2D mean
The mean value.
CPose3D mean
The mean value.
const float normalizationStd
#define THROW_EXCEPTION(msg)
size_t decimation_other_map_points
(Default=1) Only consider 1 out of this number of points from the "other" map.
mrpt::poses::CPosePDF::Ptr AlignPDF(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt) override
See base method docs.
bool se2_l2(const mrpt::tfest::TMatchingPairList &in_correspondences, mrpt::math::TPose2D &out_transformation, mrpt::math::CMatrixDouble33 *out_estimateCovariance=nullptr)
Least-squares (L2 norm) solution to finding the optimal SE(2) (x,y,yaw) between two reference frames...
Parameters for se2_l2_robust().
This file implements several operations that operate element-wise on individual or pairs of container...
A high-performance stopwatch, with typical resolution of nanoseconds.
const float ransac_mahalanobisDistanceThreshold
double pitch() const
Get the PITCH angle (in radians)
double closestSquareDistanceFromPointToLine(double Px, double Py, double x1, double y1, double x2, double y2)
Returns the square distance from a point to a line.
double yaw() const
Get the YAW angle (in radians)
mrpt::vision::TStereoCalibParams params
unsigned int nIterations
The number of executed iterations until convergence.
std::optional< std::reference_wrapper< T > > optional_ref
Shorter name for std::optional<std::reference_wrapper<T>>
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::poses::CPose3DPDF::Ptr ICP3D_Method_Classic(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
void matProductOf_AAt(const MAT_A &A)
this = A * AT
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const
Computes the matching between this and another 2D point map, which includes finding: ...
#define ASSERT_(f)
Defines an assertion mechanism.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
bool se2_l2_robust(const mrpt::tfest::TMatchingPairList &in_correspondences, const double in_normalizationStd, const TSE2RobustParams &in_ransac_params, TSE2RobustResult &out_results)
Robust least-squares (L2 norm) solution to finding the optimal SE(2) (x,y,yaw) between two reference ...
map< string, CVectorDouble > results
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
double phi() const
Get the phi angle of the 2D pose (in radians)
constexpr double DEG2RAD(const double x)
Degrees to radians.
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
string iniFile(myDataDir+string("benchmark-options.ini"))
bool onlyUniqueRobust
Additional consistency filter: "onlyKeepTheClosest" allows one correspondence for each "local map" po...
float maxDistForCorrespondence
Maximum linear distance between two points to be paired (meters)
void squareErrorVector(const mrpt::poses::CPose2D &q, std::vector< float > &out_sqErrs) const
Returns a vector with the square error between each pair of correspondences in the list...
TPoint3D_< double > TPoint3D
Lightweight 3D point.
double goodness
A goodness measure for the alignment, it is a [0,1] range indicator of percentage of correspondences...
double x() const
Common members of all points & poses classes.
void y_incr(const double v)
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
mrpt::poses::CPosePDF::Ptr ICP_Method_LM(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
Derived inverse_LLt() const
Returns the inverse of a symmetric matrix using LLt.
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double roll() const
Get the ROLL angle (in radians)
void saveToConfigFile(mrpt::config::CConfigFileBase &c, const std::string &s) const override
This method saves the options to a ".ini"-like file or memory-stored string list. ...
TICPAlgorithm
The ICP algorithm selection, used in mrpt::slam::CICP::options mrpt_slam_grp.
void pause(const std::string &msg=std::string("Press any key to continue...")) noexcept
Shows the message "Press any key to continue" (or other custom message) to the current standard outpu...
return_t square(const num_t x)
Inline function for the square of a number.
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
bool onlyKeepTheClosest
If set to true (default), only the closest correspondence will be returned.
virtual const mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
void x_incr(const double v)
size_t offset_other_map_points
Index of the first point in the "other" map to start checking for correspondences (Default=0) ...
Declares a virtual base class for all metric maps storage classes.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
constexpr double RAD2DEG(const double x)
Radians to degrees.
void setSize(size_t row, size_t col, bool zeroNewElements=false)
Changes the size of matrix, maintaining the previous contents.
The ICP algorithm return information.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
bool derivedFrom(const TRuntimeClassId *pBaseClass) const
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
bool se3_l2(const mrpt::tfest::TMatchingPairList &in_correspondences, mrpt::poses::CPose3DQuat &out_transform, double &out_scale, bool forceScaleToUnity=false)
Least-squares (L2 norm) solution to finding the optimal SE(3) transform between two reference frames ...
#define MRPT_SAVE_CONFIG_VAR_COMMENT(variableName, __comment)
TICPCovarianceMethod
ICP covariance estimation methods, used in mrpt::slam::CICP::options.
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
Parameters for the determination of matchings between point clouds, etc.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
virtual bool isEmpty() const =0
Returns true if the map is empty/no observation has been inserted.
Functions for estimating the optimal transformation between two frames of references given measuremen...
CMatrixFixed< double, ROWS, COLS > cast_double() const
mrpt::poses::CPose3DPDF::Ptr Align3DPDF(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPose3DPDFGaussian &initialEstimationPDF, mrpt::optional_ref< TMetricMapAlignmentResult > outInfo=std::nullopt) override
Output placeholder for se2_l2_robust()
double phi
Orientation (rads)
virtual void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const
Computes the matchings between this and another 3D points map - method used in 3D-ICP.
mrpt::poses::CPosePDF::Ptr ICP_Method_Classic(const mrpt::maps::CMetricMap *m1, const mrpt::maps::CMetricMap *m2, const mrpt::poses::CPosePDFGaussian &initialEstimationPDF, TReturnInfo &outInfo)
Covariance of a least-squares optimizer (includes data association uncertainty)
double quality
A measure of the 'quality' of the local minimum of the sqr.
float kernel(float x2, float rho2)
Computes: or just return the input if options.useKernel = false.