27 using namespace Eigen;
32 ConsistencyTest::ConsistencyTest(
PbMap& PBM_source,
PbMap& PBM_target)
33 : PBMSource(PBM_source), PBMTarget(PBM_target)
38 std::map<unsigned, unsigned>& matched_planes, Eigen::Matrix4f& rigidTransf)
40 double sum_depth_errors2 = 0;
57 double avError2 = sum_depth_errors2 / sum_areas;
58 return sqrt(avError2);
63 std::map<unsigned, unsigned>& matched_planes)
68 cout <<
"Insuficient matched planes " <<
matched_planes.size() << endl;
69 return Eigen::Matrix4f::Identity();
73 Matrix3f normalCovariances = Matrix3f::Zero();
74 normalCovariances(0, 0) = 1;
80 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
81 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
85 bool bPlanar_cond =
false;
93 Eigen::Vector3f planar_conditioning =
96 if (fabs(planar_conditioning(0)) > 0.33) bPlanar_cond =
true;
106 return Eigen::Matrix4f::Identity();
109 double det = Rotation.determinant();
113 aux << 1, 0, 0, 0, 1, 0, 0, 0,
det;
114 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
138 Vector3f translation;
139 Matrix3f hessian = Matrix3f::Zero();
140 Vector3f gradient = Vector3f::Zero();
141 float accum_error2 = 0.0;
150 accum_error2 += trans_error * trans_error;
158 translation = -hessian.inverse() * gradient;
182 Eigen::Matrix4f rigidTransf;
183 rigidTransf.block(0, 0, 3, 3) = Rotation;
184 rigidTransf.block(0, 3, 3, 1) = translation;
185 rigidTransf.row(3) << 0, 0, 0, 1;
191 std::map<unsigned, unsigned>& matched_planes)
195 cout <<
"Insuficient matched planes " <<
matched_planes.size() << endl;
196 return Eigen::Matrix4f::Identity();
200 Matrix3f normalCovariances = Matrix3f::Zero();
212 for (
unsigned r = 0;
r < 3;
r++)
213 for (
unsigned c = 0;
c < 3;
c++)
214 normalCovariances(0, 0) += normalCovariances(
r,
c);
216 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
217 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
221 bool bPlanar_cond =
false;
229 Eigen::Vector3f planar_conditioning =
232 if (fabs(planar_conditioning(0)) > 0.33) bPlanar_cond =
true;
242 return Eigen::Matrix4f::Identity();
245 double det = Rotation.determinant();
249 aux << 1, 0, 0, 0, 1, 0, 0, 0,
det;
250 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
269 Vector3f translation;
270 Matrix3f hessian = Matrix3f::Zero();
271 Vector3f gradient = Vector3f::Zero();
296 for (
unsigned r = 0;
r < 3;
r++)
297 for (
unsigned c = 0;
c < 3;
c++) hessian(0, 0) += hessian(
r,
c);
299 translation = -hessian.inverse() * gradient;
323 Eigen::Matrix4f rigidTransf;
324 rigidTransf.block(0, 0, 3, 3) = Rotation;
325 rigidTransf.block(0, 3, 3, 1) = translation;
326 rigidTransf.row(3) << 0, 0, 0, 1;
331 std::map<unsigned, unsigned>& matched_planes, Eigen::Matrix4f& rigidTransf,
332 Eigen::Matrix<float, 6, 6>& covarianceM)
336 cout <<
"Insuficient matched planes " <<
matched_planes.size() << endl;
345 JacobiSVD<MatrixXf> svd_cond(normalVectors, ComputeThinU | ComputeThinV);
347 if (svd_cond.singularValues()[0] / svd_cond.singularValues()[1] > 10)
351 Matrix3f normalCovariances = Matrix3f::Zero();
362 for (
unsigned r = 0;
r < 3;
r++)
363 for (
unsigned c = 0;
c < 3;
c++)
364 normalCovariances(0, 0) += fabs(normalCovariances(
r,
c));
366 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
368 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
369 double det = Rotation.determinant();
373 aux << 1, 0, 0, 0, 1, 0, 0, 0,
det;
374 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
378 Vector3f translation;
379 Matrix3f hessian = Matrix3f::Zero();
380 Vector3f gradient = Vector3f::Zero();
398 for (
unsigned r = 0;
r < 3;
r++)
399 for (
unsigned c = 0;
c < 3;
c++) hessian(0, 0) += fabs(hessian(
r,
c));
401 translation = -hessian.inverse() * gradient;
406 rigidTransf.block(0, 0, 3, 3) = Rotation;
407 rigidTransf.block(0, 3, 3, 1) = translation;
408 rigidTransf.row(3) << 0, 0, 0, 1;
411 covarianceM.block(0, 0, 3, 3) = hessian;
414 covarianceM.block(3, 3, 3, 3) = normalCovariances;
420 std::map<unsigned, unsigned>& matched_planes)
423 Matrix3f normalCovariances = Matrix3f::Zero();
428 normalCovariances(1, 1) += 100;
430 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
431 Matrix3f Rotation = svd.matrixU() * svd.matrixV().transpose();
433 if (Rotation.determinant() < 0)
435 Rotation = -Rotation;
438 Vector3f translation;
439 Vector3f center_data = Vector3f::Zero(), center_model = Vector3f::Zero();
440 Vector3f centerFull_data = Vector3f::Zero(),
441 centerFull_model = Vector3f::Zero();
442 unsigned numFull = 0, numNonStruct = 0;
465 (-centerFull_model + Rotation * centerFull_data) / numFull;
469 translation = (-center_model + Rotation * center_data) / numNonStruct;
476 Eigen::Matrix4f rigidTransf;
477 rigidTransf.block(0, 0, 3, 3) = Rotation;
478 rigidTransf.block(0, 3, 3, 1) = translation;
479 rigidTransf.row(3) << 0, 0, 0, 1;
484 std::map<unsigned, unsigned>& matched_planes)
487 Eigen::Matrix4f rigidTransf =
495 cout <<
"INITIALIZATION POSE \n" << rigidTransf << endl;
496 cout <<
"Alignment error " << alignmentError << endl;
500 double improveRate = 0;
501 while (nIter < 10 && improveRate < 0.999)
505 Vector3f ptInModelRef;
506 Eigen::Matrix<float, 6, 1> v6JacDepthPlane;
507 Eigen::Matrix<float, 6, 1> v6Error = Eigen::Matrix<float, 6, 1>::Zero();
508 Eigen::Matrix<float, 6, 6> m6Hessian =
509 Eigen::Matrix<float, 6, 6>::Zero();
529 m6Hessian += v6JacDepthPlane * v6JacDepthPlane.transpose();
530 v6Error += v6JacDepthPlane * depthError;
533 Eigen::Matrix<float, 6, 1> updatedSE3 =
534 (m6Hessian.inverse() * v6Error).
transpose();
536 _updatedSE3(0) = updatedSE3(0);
537 _updatedSE3(1) = updatedSE3(1);
538 _updatedSE3(2) = updatedSE3(2);
539 _updatedSE3(3) = updatedSE3(3);
540 _updatedSE3(4) = updatedSE3(4);
541 _updatedSE3(5) = updatedSE3(5);
544 Eigen::Matrix4f updatePose;
545 updatePose << CMatUpdate(0, 0), CMatUpdate(0, 1), CMatUpdate(0, 2),
546 CMatUpdate(0, 3), CMatUpdate(1, 0), CMatUpdate(1, 1),
547 CMatUpdate(1, 2), CMatUpdate(1, 3), CMatUpdate(2, 0),
548 CMatUpdate(2, 1), CMatUpdate(2, 2), CMatUpdate(2, 3), 0, 0, 0, 1;
549 Eigen::Matrix4f tempPose =
compose(updatePose, rigidTransf);
552 cout <<
"New alignment error " << newError << endl;
555 if (newError < alignmentError)
557 improveRate = newError / alignmentError;
558 alignmentError = newError;
559 rigidTransf = tempPose;
564 cout <<
"Not converging in iteration " << nIter << endl;
573 cout <<
"Consistency test converged after " << nIter << endl;
582 assert(
size(matched_planes, 1) == 8 &&
size(matched_planes, 2) == 3);
585 Matrix3f normalCovariances = Matrix3f::Zero();
586 normalCovariances(0, 0) = 1;
587 for (
unsigned i = 0; i < 3; i++)
589 Vector3f n_i = Vector3f(
590 matched_planes(0, i), matched_planes(1, i), matched_planes(2, i));
591 Vector3f n_ii = Vector3f(
592 matched_planes(4, i), matched_planes(5, i), matched_planes(6, i));
593 normalCovariances += n_i * n_ii.transpose();
598 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
599 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
610 double det = Rotation.determinant();
614 aux << 1, 0, 0, 0, 1, 0, 0, 0,
det;
615 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
619 Vector3f translation;
620 Matrix3f hessian = Matrix3f::Zero();
621 Vector3f gradient = Vector3f::Zero();
623 for (
unsigned i = 0; i < 3; i++)
626 (matched_planes(3, i) - matched_planes(7, i));
630 Vector3f n_i = Vector3f(
631 matched_planes(0, i), matched_planes(1, i), matched_planes(2, i));
632 hessian += n_i * n_i.transpose();
633 gradient += n_i * trans_error;
635 translation = -hessian.inverse() * gradient;
647 rigidTransf(0, 0) = Rotation(0, 0);
648 rigidTransf(0, 1) = Rotation(0, 1);
649 rigidTransf(0, 2) = Rotation(0, 2);
650 rigidTransf(1, 0) = Rotation(1, 0);
651 rigidTransf(1, 1) = Rotation(1, 1);
652 rigidTransf(1, 2) = Rotation(1, 2);
653 rigidTransf(2, 0) = Rotation(2, 0);
654 rigidTransf(2, 1) = Rotation(2, 1);
655 rigidTransf(2, 2) = Rotation(2, 2);
656 rigidTransf(0, 3) = translation(0);
657 rigidTransf(1, 3) = translation(1);
658 rigidTransf(2, 3) = translation(2);
659 rigidTransf(3, 0) = 0;
660 rigidTransf(3, 1) = 0;
661 rigidTransf(3, 2) = 0;
662 rigidTransf(3, 3) = 1;
670 vector<CMatrixDouble>& fitModels)
673 ASSERT_(useIndices.size() == 3);
682 for (
unsigned i = 0; i < 3; i++)
683 corresp.col(i) = planeCorresp.col(useIndices[i]);
698 const CMatrixDouble& planeCorresp,
const vector<CMatrixDouble>& testModels,
699 const double distanceThreshold,
unsigned int& out_bestModelIndex,
702 ASSERT_(testModels.size() == 1)
703 out_bestModelIndex = 0;
706 Eigen::Matrix3f Rotation;
707 Rotation << M(0, 0), M(0, 1), M(0, 2), M(1, 0), M(1, 1), M(1, 2), M(2, 0),
709 Eigen::Vector3f translation;
710 translation << M(0, 3), M(1, 3), M(2, 3);
714 const size_t N =
size(planeCorresp, 2);
715 out_inlierIndices.clear();
716 out_inlierIndices.reserve(100);
717 for (
size_t i = 0; i < N; i++)
719 const Eigen::Vector3f n_i = Eigen::Vector3f(
720 planeCorresp(0, i), planeCorresp(1, i), planeCorresp(2, i));
721 const Eigen::Vector3f n_ii =
724 planeCorresp(4, i), planeCorresp(5, i), planeCorresp(6, i));
725 const float d_error = fabs(
726 (planeCorresp(7, i) - translation.dot(n_i)) - planeCorresp(3, i));
727 const float angle_error = (n_i.cross(n_ii)).
norm();
729 if (d_error < distanceThreshold)
730 if (angle_error < distanceThreshold)
732 out_inlierIndices.push_back(i);
741 ASSERT_(useIndices.size() == 3)
743 const Eigen::Vector3f n_1 = Eigen::Vector3f(
744 planeCorresp(0, useIndices[0]), planeCorresp(1, useIndices[0]),
745 planeCorresp(2, useIndices[0]));
746 const Eigen::Vector3f n_2 = Eigen::Vector3f(
747 planeCorresp(0, useIndices[1]), planeCorresp(1, useIndices[1]),
748 planeCorresp(2, useIndices[1]));
749 const Eigen::Vector3f n_3 = Eigen::Vector3f(
750 planeCorresp(0, useIndices[2]), planeCorresp(1, useIndices[2]),
751 planeCorresp(2, useIndices[2]));
755 if (fabs(n_1.dot(n_2.cross(n_3))) < 0.9)
return true;
764 std::map<unsigned, unsigned>& matched_planes)
771 cout <<
"Insuficient matched planes " <<
matched_planes.size() << endl;
772 return Eigen::Matrix4f::Identity();
807 cout <<
"Size planeCorresp: " <<
size(planeCorresp, 2) << endl;
808 cout <<
"RANSAC finished: " << inliers.size() <<
" inliers: " << inliers
809 <<
" . \nBest model: \n" 810 << best_model << endl;
813 Eigen::Matrix4f rigidTransf;
814 rigidTransf << best_model(0, 0), best_model(0, 1), best_model(0, 2),
815 best_model(0, 3), best_model(1, 0), best_model(1, 1), best_model(1, 2),
816 best_model(1, 3), best_model(2, 0), best_model(2, 1), best_model(2, 2),
817 best_model(2, 3), 0, 0, 0, 1;
EIGEN_STRONG_INLINE Scalar det() const
Eigen::Matrix4f estimatePose(std::map< unsigned, unsigned > &matched_planes)
void ransacPlaneAlignment_fit(const CMatrixDouble &planeCorresp, const mrpt::vector_size_t &useIndices, vector< CMatrixDouble > &fitModels)
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...
Eigen::Matrix4f estimatePoseRANSAC(std::map< unsigned, unsigned > &matched_planes)
bool execute(const CMatrixTemplateNumeric< NUMTYPE > &data, const TRansacFitFunctor &fit_func, const TRansacDistanceFunctor &dist_func, const TRansacDegenerateFunctor °en_func, const double distanceThreshold, const unsigned int minimumSizeSamplesToFit, mrpt::vector_size_t &out_best_inliers, CMatrixTemplateNumeric< NUMTYPE > &out_best_model, const double prob_good_sample=0.999, const size_t maxIter=2000) const
An implementation of the RANSAC algorithm for robust fitting of models to data.
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
bool ransac3Dplane_degenerate(const CMatrixDouble &planeCorresp, const mrpt::vector_size_t &useIndices)
Return "true" if the selected points are a degenerate (invalid) case.
Eigen::Matrix4f initPose2D(std::map< unsigned, unsigned > &matched_planes)
CMatrixDouble getAlignment(const CMatrixDouble &matched_planes)
GLsizei GLboolean transpose
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double calcAlignmentError(std::map< unsigned, unsigned > &matched_planes, Eigen::Matrix4f &rigidTransf)
! Get diamond of points around the center.
GLdouble GLdouble GLdouble r
Eigen::Matrix4f initPose(std::map< unsigned, unsigned > &matched_planes)
A matrix of dynamic size.
std::vector< size_t > vector_size_t
std::map< unsigned, unsigned > matched_planes
void ransac3Dplane_distance(const CMatrixDouble &planeCorresp, const vector< CMatrixDouble > &testModels, const double distanceThreshold, unsigned int &out_bestModelIndex, mrpt::vector_size_t &out_inlierIndices)
std::vector< Plane > vPlanes
A generic RANSAC implementation with models as matrices.
static CPose3D exp(const mrpt::math::CArrayNumeric< double, 6 > &vect, bool pseudo_exponential=false)
Exponentiate a Vector in the SE(3) Lie Algebra to generate a new CPose3D (static method).
A class used to store a Plane-based Map (PbMap).
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
CONTAINER::Scalar norm(const CONTAINER &v)
bool estimatePoseWithCovariance(std::map< unsigned, unsigned > &matched_planes, Eigen::Matrix4f &rigidTransf, Eigen::Matrix< float, 6, 6 > &covarianceM)
Eigen::Matrix< dataType, 3, 1 > compose(Eigen::Matrix< dataType, 4, 4 > &pose, Eigen::Matrix< dataType, 3, 1 > &point)
std::vector< size_t > vector_size_t
Eigen::Matrix4f getRTwithModel(std::map< unsigned, unsigned > &matched_planes)