44 using namespace Eigen;
67 LOG_INFO_STREAM(
"PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 2D.");
72 LOG_INFO_STREAM(
"PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 4-DOF (yaw,x,y,z).");
76 LOG_INFO_STREAM(
"PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 3D.");
94 LOG_INFO_STREAM(
"PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 2D.");
99 LOG_INFO_STREAM(
"PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 4-DOF (yaw,x,y,z).");
103 LOG_INFO_STREAM(
"PointMatcher::PointToPlaneErrorMinimizer - minimization will be in 3D.");
108 template<
typename T,
typename MatrixA,
typename Vector>
110 assert(A.cols() == A.rows());
111 assert(b.cols() == 1);
112 assert(b.rows() == A.rows());
113 assert(
x.cols() == 1);
114 assert(
x.rows() == A.cols());
118 BOOST_AUTO(Aqr, A.fullPivHouseholderQr());
119 if (!Aqr.isInvertible())
122 const int rank = Aqr.rank();
123 const int rows = A.rows();
124 const Matrix Q1t = Aqr.matrixQ().transpose().block(0, 0, rank, rows);
125 const Matrix R1 = (Q1t * A * Aqr.colsPermutation()).block(0, 0, rank, rows);
127 const bool findMinimalNormSolution =
true;
130 if(findMinimalNormSolution){
132 x = R1.template triangularView<Eigen::Upper>().transpose() * (R1 * R1.transpose()).llt().solve(Q1t * b);
135 x.block(0, 0, rank, 1) = R1.block(0, 0, rank, rank).template triangularView<Eigen::Upper>().solve(Q1t * b);
136 x.block(rank, 0, rows - rank, 1).setZero();
139 x = Aqr.colsPermutation() *
x;
141 BOOST_AUTO(ax , (A *
x).eval());
142 if (!b.isApprox(ax, 1e-5)) {
143 LOG_INFO_STREAM(
"PointMatcher::icp - encountered almost singular matrix while minimizing point to plane distance. QR solution was too inaccurate. Trying more accurate approach using double precision SVD.");
144 x = A.template cast<double>().jacobiSvd(ComputeThinU | ComputeThinV).solve(b.template cast<double>()).template cast<T>();
147 if((b - ax).norm() > 1e-5 * std::max(A.norm() *
x.norm(), b.norm())){
148 LOG_WARNING_STREAM(
"PointMatcher::icp - encountered numerically singular matrix while minimizing point to plane distance and the current workaround remained inaccurate."
149 <<
" b=" << b.transpose()
150 <<
" !~ A * x=" << (ax).transpose().eval()
151 <<
": ||b- ax||=" << (b - ax).norm()
152 <<
", ||b||=" << b.norm()
153 <<
", ||ax||=" << ax.norm());
159 x = A.llt().solve(b);
167 return compute_in_place(mPts);
178 int forcedDim = dim - 1;
179 if(force2D && dim == 4)
192 assert(normalRef.rows() > 0);
206 matrixGamma << 0,-1, 0,
209 cross = ((matrixGamma*mPts.
reading.
features).transpose()*normalRef).diagonal().transpose();
215 Matrix wF(normalRef.rows()+ cross.rows(), normalRef.cols());
216 Matrix F(normalRef.rows()+ cross.rows(), normalRef.cols());
218 for(
int i=0; i < cross.rows(); i++)
220 wF.row(i) = mPts.
weights.array() * cross.row(i).array();
221 F.row(i) = cross.row(i);
223 for(
int i=0; i < normalRef.rows(); i++)
225 wF.row(i + cross.rows()) = mPts.
weights.array() * normalRef.row(i).array();
226 F.row(i + cross.rows()) = normalRef.row(i);
230 const Matrix A = wF * F.transpose();
235 Matrix dotProd = Matrix::Zero(1, normalRef.cols());
237 for(
int i=0; i<normalRef.rows(); i++)
239 dotProd += (deltas.row(i).array() * normalRef.row(i).array()).matrix();
243 const Vector b = -(wF * dotProd.transpose());
247 solvePossiblyUnderdeterminedLinearSystem<T>(A, b,
x);
251 if(dim == 4 && !force2D)
253 Eigen::Transform<T, 3, Eigen::Affine> transform;
263 transform = Eigen::AngleAxis<T>(
x.head(3).norm(),
x.head(3).normalized());
268 transform = Eigen::AngleAxis<T>(
x(0), unitZ);
278 transform.translation() =
x.segment(3, 3);
281 transform.translation() =
x.segment(1, 3);
284 mOut = transform.matrix();
291 mOut.block(0, 0, dim-1, dim-1) = Matrix::Identity(dim-1, dim-1);
296 Eigen::Transform<T, 2, Eigen::Affine> transform;
297 transform = Eigen::Rotation2D<T> (
x(0));
298 transform.translation() =
x.segment(1, 2);
302 mOut = Matrix::Identity(dim, dim);
303 mOut.topLeftCorner(2, 2) = transform.matrix().topLeftCorner(2, 2);
304 mOut.topRightCorner(2, 1) = transform.matrix().topRightCorner(2, 1);
308 mOut = transform.matrix();
322 int forcedDim = dim - 1;
323 if(force2D && dim == 4)
336 assert(normalRef.rows() > 0);
341 Matrix dotProd = Matrix::Zero(1, normalRef.cols());
342 for(
int i = 0; i < normalRef.rows(); i++)
344 dotProd += (deltas.row(i).array() * normalRef.row(i).array()).matrix();
347 dotProd = (mPts.
weights.row(0).array() * dotProd.array().square()).matrix();
350 return dotProd.sum();
361 assert(matches.
ids.rows() > 0);
374 const bool hasReadingNoise = this->lastErrorElements.reading.descriptorExists(
"simpleSensorNoise");
375 const bool hasReferenceNoise = this->lastErrorElements.reference.descriptorExists(
"simpleSensorNoise");
376 const bool hasReferenceDensity = this->lastErrorElements.reference.descriptorExists(
"densities");
378 const int nbPoints = this->lastErrorElements.reading.features.cols();
379 const int dim = this->lastErrorElements.reading.features.rows();
384 throw std::runtime_error(
"Error, last error element empty. Error minimizer needs to be called at least once before using this method.");
387 Eigen::Array<T, 1, Eigen::Dynamic> uncertainties(nbPoints);
390 if (hasReadingNoise && hasReferenceNoise && hasReferenceDensity)
394 Matrix densities = this->lastErrorElements.reference.getDescriptorViewByName(
"densities");
395 vector<T>
values(densities.data(), densities.data() + densities.size());
402 const T medianRadius = 1.0/
pow(medianDensity, 1/3.0);
404 uncertainties = (medianRadius +
405 this->lastErrorElements.reading.getDescriptorViewByName(
"simpleSensorNoise").array() +
406 this->lastErrorElements.reference.getDescriptorViewByName(
"simpleSensorNoise").array());
408 else if(hasReadingNoise && hasReferenceNoise)
410 uncertainties = this->lastErrorElements.reading.getDescriptorViewByName(
"simpleSensorNoise") +
411 this->lastErrorElements.reference.getDescriptorViewByName(
"simpleSensorNoise");
413 else if(hasReadingNoise)
415 uncertainties = this->lastErrorElements.reading.getDescriptorViewByName(
"simpleSensorNoise");
417 else if(hasReferenceNoise)
419 uncertainties = this->lastErrorElements.reference.getDescriptorViewByName(
"simpleSensorNoise");
423 LOG_INFO_STREAM(
"PointToPlaneErrorMinimizer - warning, no sensor noise and density. Using best estimate given outlier rejection instead.");
424 return this->getWeightedPointUsedRatio();
428 const Vector dists = (this->lastErrorElements.reading.features.topRows(dim-1) - this->lastErrorElements.reference.features.topRows(dim-1)).colwise().norm();
434 int nbUniquePoint = 1;
435 Vector lastValidPoint = this->lastErrorElements.reading.features.col(0) * 2.;
436 for(
int i=0; i < nbPoints; i++)
438 const Vector point = this->lastErrorElements.reading.features.col(i);
440 if(lastValidPoint != point)
449 lastValidPoint = point;
457 if(point != this->lastErrorElements.reading.features.col(i-1))
464 return (T)count/(T)(nbUniquePoint + this->lastErrorElements.nbRejectedPoints);