28 using namespace Eigen;
33 ConsistencyTest::ConsistencyTest(
PbMap& PBM_source,
PbMap& PBM_target)
34 : PBMSource(PBM_source), PBMTarget(PBM_target)
39 std::map<unsigned, unsigned>& matched_planes, Eigen::Matrix4f& rigidTransf)
41 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;
79 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
80 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
84 bool bPlanar_cond =
false;
92 Eigen::Vector3f planar_conditioning =
95 if (fabs(planar_conditioning(0)) > 0.33) bPlanar_cond =
true;
105 return Eigen::Matrix4f::Identity();
108 double det = Rotation.determinant();
112 aux << 1, 0, 0, 0, 1, 0, 0, 0, det;
113 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
137 Vector3f translation;
138 Matrix3f hessian = Matrix3f::Zero();
139 Vector3f gradient = Vector3f::Zero();
140 float accum_error2 = 0.0;
148 accum_error2 += trans_error * trans_error;
156 translation = -hessian.inverse() * gradient;
180 Eigen::Matrix4f rigidTransf;
181 rigidTransf.block<3, 3>(0, 0) = Rotation;
182 rigidTransf.block(0, 3, 3, 1) = translation;
183 rigidTransf.row(3) << 0, 0, 0, 1;
189 std::map<unsigned, unsigned>& matched_planes)
193 cout <<
"Insuficient matched planes " <<
matched_planes.size() << endl;
194 return Eigen::Matrix4f::Identity();
198 Matrix3f normalCovariances = Matrix3f::Zero();
209 for (
unsigned r = 0;
r < 3;
r++)
210 for (
unsigned c = 0;
c < 3;
c++)
211 normalCovariances(0, 0) += normalCovariances(
r,
c);
213 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
214 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
218 bool bPlanar_cond =
false;
226 Eigen::Vector3f planar_conditioning =
229 if (fabs(planar_conditioning(0)) > 0.33) bPlanar_cond =
true;
239 return Eigen::Matrix4f::Identity();
242 double det = Rotation.determinant();
246 aux << 1, 0, 0, 0, 1, 0, 0, 0, det;
247 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
266 Vector3f translation;
267 Matrix3f hessian = Matrix3f::Zero();
268 Vector3f gradient = Vector3f::Zero();
292 for (
unsigned r = 0;
r < 3;
r++)
293 for (
unsigned c = 0;
c < 3;
c++) hessian(0, 0) += hessian(
r,
c);
295 translation = -hessian.inverse() * gradient;
319 Eigen::Matrix4f rigidTransf;
320 rigidTransf.block<3, 3>(0, 0) = Rotation;
321 rigidTransf.block(0, 3, 3, 1) = translation;
322 rigidTransf.row(3) << 0, 0, 0, 1;
327 std::map<unsigned, unsigned>& matched_planes, Eigen::Matrix4f& rigidTransf,
332 cout <<
"Insuficient matched planes " <<
matched_planes.size() << endl;
341 JacobiSVD<MatrixXf> svd_cond(normalVectors, ComputeThinU | ComputeThinV);
343 if (svd_cond.singularValues()[0] / svd_cond.singularValues()[1] > 10)
347 Matrix3f normalCovariances = Matrix3f::Zero();
357 for (
unsigned r = 0;
r < 3;
r++)
358 for (
unsigned c = 0;
c < 3;
c++)
359 normalCovariances(0, 0) += fabs(normalCovariances(
r,
c));
361 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
363 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
364 double det = Rotation.determinant();
368 aux << 1, 0, 0, 0, 1, 0, 0, 0, det;
369 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
373 Vector3f translation;
374 Matrix3f hessian = Matrix3f::Zero();
375 Vector3f gradient = Vector3f::Zero();
392 for (
unsigned r = 0;
r < 3;
r++)
393 for (
unsigned c = 0;
c < 3;
c++) hessian(0, 0) += fabs(hessian(
r,
c));
395 translation = -hessian.inverse() * gradient;
400 rigidTransf.block<3, 3>(0, 0) = Rotation;
401 rigidTransf.block(0, 3, 3, 1) = translation;
402 rigidTransf.row(3) << 0, 0, 0, 1;
405 covarianceM.block<3, 3>(0, 0) = hessian;
408 covarianceM.block(3, 3, 3, 3) = normalCovariances;
414 std::map<unsigned, unsigned>& matched_planes)
417 Matrix3f normalCovariances = Matrix3f::Zero();
421 normalCovariances(1, 1) += 100;
423 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
424 Matrix3f Rotation = svd.matrixU() * svd.matrixV().transpose();
426 if (Rotation.determinant() < 0)
428 Rotation = -Rotation;
431 Vector3f translation;
432 Vector3f center_data = Vector3f::Zero(), center_model = Vector3f::Zero();
433 Vector3f centerFull_data = Vector3f::Zero(),
434 centerFull_model = Vector3f::Zero();
435 unsigned numFull = 0, numNonStruct = 0;
457 (-centerFull_model + Rotation * centerFull_data) / numFull;
461 translation = (-center_model + Rotation * center_data) / numNonStruct;
468 Eigen::Matrix4f rigidTransf;
469 rigidTransf.block<3, 3>(0, 0) = Rotation;
470 rigidTransf.block(0, 3, 3, 1) = translation;
471 rigidTransf.row(3) << 0, 0, 0, 1;
476 std::map<unsigned, unsigned>& matched_planes)
479 Eigen::Matrix4f rigidTransf =
487 cout <<
"INITIALIZATION POSE \n" << rigidTransf << endl;
488 cout <<
"Alignment error " << alignmentError << endl;
492 double improveRate = 0;
493 while (nIter < 10 && improveRate < 0.999)
497 Vector3f ptInModelRef;
520 m6Hessian += v6JacDepthPlane * v6JacDepthPlane.transpose();
521 v6Error += v6JacDepthPlane * depthError;
525 (m6Hessian.inverse() * v6Error).
transpose();
526 const auto _updatedSE3 =
530 .getHomogeneousMatrix(CMatUpdate);
531 Eigen::Matrix4f updatePose;
532 updatePose << CMatUpdate(0, 0), CMatUpdate(0, 1), CMatUpdate(0, 2),
533 CMatUpdate(0, 3), CMatUpdate(1, 0), CMatUpdate(1, 1),
534 CMatUpdate(1, 2), CMatUpdate(1, 3), CMatUpdate(2, 0),
535 CMatUpdate(2, 1), CMatUpdate(2, 2), CMatUpdate(2, 3), 0, 0, 0, 1;
536 Eigen::Matrix4f tempPose =
compose(updatePose, rigidTransf);
539 cout <<
"New alignment error " << newError << endl;
542 if (newError < alignmentError)
544 improveRate = newError / alignmentError;
545 alignmentError = newError;
546 rigidTransf = tempPose;
551 cout <<
"Not converging in iteration " << nIter << endl;
560 cout <<
"Consistency test converged after " << nIter << endl;
569 assert(matched_planes.
rows() == 8 && matched_planes.
cols() == 3);
572 Matrix3f normalCovariances = Matrix3f::Zero();
573 normalCovariances(0, 0) = 1;
574 for (
unsigned i = 0; i < 3; i++)
576 Vector3f n_i = Vector3f(
577 matched_planes(0, i), matched_planes(1, i), matched_planes(2, i));
578 Vector3f n_ii = Vector3f(
579 matched_planes(4, i), matched_planes(5, i), matched_planes(6, i));
580 normalCovariances += n_i * n_ii.transpose();
585 JacobiSVD<MatrixXf> svd(normalCovariances, ComputeThinU | ComputeThinV);
586 Matrix3f Rotation = svd.matrixV() * svd.matrixU().transpose();
597 double det = Rotation.determinant();
601 aux << 1, 0, 0, 0, 1, 0, 0, 0, det;
602 Rotation = svd.matrixV() * aux * svd.matrixU().transpose();
606 Vector3f translation;
607 Matrix3f hessian = Matrix3f::Zero();
608 Vector3f gradient = Vector3f::Zero();
610 for (
unsigned i = 0; i < 3; i++)
613 (matched_planes(3, i) - matched_planes(7, i));
617 Vector3f n_i = Vector3f(
618 matched_planes(0, i), matched_planes(1, i), matched_planes(2, i));
619 hessian += n_i * n_i.transpose();
620 gradient += n_i * trans_error;
622 translation = -hessian.inverse() * gradient;
634 rigidTransf(0, 0) = Rotation(0, 0);
635 rigidTransf(0, 1) = Rotation(0, 1);
636 rigidTransf(0, 2) = Rotation(0, 2);
637 rigidTransf(1, 0) = Rotation(1, 0);
638 rigidTransf(1, 1) = Rotation(1, 1);
639 rigidTransf(1, 2) = Rotation(1, 2);
640 rigidTransf(2, 0) = Rotation(2, 0);
641 rigidTransf(2, 1) = Rotation(2, 1);
642 rigidTransf(2, 2) = Rotation(2, 2);
643 rigidTransf(0, 3) = translation(0);
644 rigidTransf(1, 3) = translation(1);
645 rigidTransf(2, 3) = translation(2);
646 rigidTransf(3, 0) = 0;
647 rigidTransf(3, 1) = 0;
648 rigidTransf(3, 2) = 0;
649 rigidTransf(3, 3) = 1;
656 const CMatrixDouble& planeCorresp,
const std::vector<size_t>& useIndices,
657 vector<CMatrixDouble>& fitModels)
660 ASSERT_(useIndices.size() == 3);
669 for (
unsigned i = 0; i < 3; i++)
670 corresp.
col(i) = planeCorresp.
col(useIndices[i]);
685 const CMatrixDouble& planeCorresp,
const vector<CMatrixDouble>& testModels,
686 const double distanceThreshold,
unsigned int& out_bestModelIndex,
687 std::vector<size_t>& out_inlierIndices)
689 ASSERT_(testModels.size() == 1);
690 out_bestModelIndex = 0;
693 Eigen::Matrix3f Rotation;
694 Rotation << M(0, 0), M(0, 1), M(0, 2), M(1, 0), M(1, 1), M(1, 2), M(2, 0),
696 Eigen::Vector3f translation;
697 translation << M(0, 3), M(1, 3), M(2, 3);
699 ASSERT_(M.rows() == 4 && M.cols() == 4);
701 const size_t N = planeCorresp.
cols();
702 out_inlierIndices.clear();
703 out_inlierIndices.reserve(100);
704 for (
size_t i = 0; i < N; i++)
706 const Eigen::Vector3f n_i = Eigen::Vector3f(
707 planeCorresp(0, i), planeCorresp(1, i), planeCorresp(2, i));
708 const Eigen::Vector3f n_ii =
711 planeCorresp(4, i), planeCorresp(5, i), planeCorresp(6, i));
712 const float d_error = fabs(
713 (planeCorresp(7, i) - translation.
dot(n_i)) - planeCorresp(3, i));
714 const float angle_error = (n_i.cross(n_ii)).
norm();
716 if (d_error < distanceThreshold)
717 if (angle_error < distanceThreshold)
719 out_inlierIndices.push_back(i);
726 const CMatrixDouble& planeCorresp,
const std::vector<size_t>& useIndices)
728 ASSERT_(useIndices.size() == 3);
730 const Eigen::Vector3f n_1 = Eigen::Vector3f(
731 planeCorresp(0, useIndices[0]), planeCorresp(1, useIndices[0]),
732 planeCorresp(2, useIndices[0]));
733 const Eigen::Vector3f n_2 = Eigen::Vector3f(
734 planeCorresp(0, useIndices[1]), planeCorresp(1, useIndices[1]),
735 planeCorresp(2, useIndices[1]));
736 const Eigen::Vector3f n_3 = Eigen::Vector3f(
737 planeCorresp(0, useIndices[2]), planeCorresp(1, useIndices[2]),
738 planeCorresp(2, useIndices[2]));
742 if (fabs(n_1.dot(n_2.cross(n_3))) < 0.9)
return true;
751 std::map<unsigned, unsigned>& matched_planes)
758 cout <<
"Insuficient matched planes " <<
matched_planes.size() << endl;
759 return Eigen::Matrix4f::Identity();
778 std::vector<size_t> inliers;
787 inliers, best_model, 0.99999);
792 cout <<
"Size planeCorresp: " << planeCorresp.cols() << endl;
793 cout <<
"RANSAC finished: " << inliers.size() <<
" inliers: " << inliers
794 <<
" . \nBest model: \n" 795 << best_model << endl;
798 Eigen::Matrix4f rigidTransf;
799 rigidTransf << best_model(0, 0), best_model(0, 1), best_model(0, 2),
800 best_model(0, 3), best_model(1, 0), best_model(1, 1), best_model(1, 2),
801 best_model(1, 3), best_model(2, 0), best_model(2, 1), best_model(2, 2),
802 best_model(2, 3), 0, 0, 0, 1;
A compile-time fixed-size numeric matrix container.
Eigen::Matrix4f estimatePose(std::map< unsigned, unsigned > &matched_planes)
bool ransac3Dplane_degenerate(const CMatrixDouble &planeCorresp, const std::vector< size_t > &useIndices)
Return "true" if the selected points are a degenerate (invalid) case.
Eigen::Matrix4f estimatePoseRANSAC(std::map< unsigned, unsigned > &matched_planes)
void ransac3Dplane_distance(const CMatrixDouble &planeCorresp, const vector< CMatrixDouble > &testModels, const double distanceThreshold, unsigned int &out_bestModelIndex, std::vector< size_t > &out_inlierIndices)
#define ASSERT_(f)
Defines an assertion mechanism.
This base provides a set of functions for maths stuff.
Scalar dot(const CVectorDynamic< Scalar > &v) const
dot product of this \cdot v
void ransacPlaneAlignment_fit(const CMatrixDouble &planeCorresp, const std::vector< size_t > &useIndices, vector< CMatrixDouble > &fitModels)
Eigen::Matrix4f initPose2D(std::map< unsigned, unsigned > &matched_planes)
size_type rows() const
Number of rows in the matrix.
size_type cols() const
Number of columns in the matrix.
CMatrixDouble getAlignment(const CMatrixDouble &matched_planes)
Traits for SE(n), rigid-body transformations in R^n space.
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)
std::map< unsigned, unsigned > matched_planes
std::vector< Plane > vPlanes
A generic RANSAC implementation with models as matrices.
bool execute(const CMatrixDynamic< NUMTYPE > &data, const TRansacFitFunctor &fit_func, const TRansacDistanceFunctor &dist_func, const TRansacDegenerateFunctor °en_func, const double distanceThreshold, const unsigned int minimumSizeSamplesToFit, std::vector< size_t > &out_best_inliers, CMatrixDynamic< 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 class used to store a Plane-based Map (PbMap).
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)
Eigen::Matrix4f getRTwithModel(std::map< unsigned, unsigned > &matched_planes)