Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "ErrorMinimizersImpl.h"
00037 #include "PointMatcherPrivate.h"
00038 #include "Eigen/SVD"
00039
00040 using namespace Eigen;
00041
00042 template<typename T>
00043 typename PointMatcher<T>::TransformationParameters PointToPointSimilarityErrorMinimizer<T>::compute(const ErrorElements& mPts_const)
00044 {
00045
00046
00047
00048 ErrorElements mPts = mPts_const;
00049
00050
00051 const int dimCount(mPts.reading.features.rows());
00052
00053
00054
00055
00056
00057 const Vector w = mPts.weights.row(0);
00058 const T w_sum_inv = T(1.)/w.sum();
00059 const Vector meanReading =
00060 (mPts.reading.features.topRows(dimCount-1).array().rowwise() * w.array().transpose()).rowwise().sum() * w_sum_inv;
00061 const Vector meanReference =
00062 (mPts.reference.features.topRows(dimCount-1).array().rowwise() * w.array().transpose()).rowwise().sum() * w_sum_inv;
00063
00064
00065
00066 mPts.reading.features.topRows(dimCount-1).colwise() -= meanReading;
00067 mPts.reference.features.topRows(dimCount-1).colwise() -= meanReference;
00068
00069 const T sigma = mPts.reading.features.topRows(dimCount-1).colwise().squaredNorm().cwiseProduct(w.transpose()).sum();
00070
00071
00072 const Matrix m(mPts.reference.features.topRows(dimCount-1) * w.asDiagonal()
00073 * mPts.reading.features.topRows(dimCount-1).transpose());
00074 const JacobiSVD<Matrix> svd(m, ComputeThinU | ComputeThinV);
00075 Matrix rotMatrix(svd.matrixU() * svd.matrixV().transpose());
00076 typedef typename JacobiSVD<Matrix>::SingularValuesType SingularValuesType;
00077 SingularValuesType singularValues = svd.singularValues();
00078
00079
00080
00081
00082 if (rotMatrix.determinant() < 0.)
00083 {
00084 Matrix tmpV = svd.matrixV().transpose();
00085 tmpV.row(dimCount-2) *= -1.;
00086 rotMatrix = svd.matrixU() * tmpV;
00087 singularValues(dimCount-2) *= -1.;
00088 }
00089 T scale = singularValues.sum() / sigma;
00090 if (sigma < 0.0001) scale = T(1);
00091 const Vector trVector(meanReference - scale * rotMatrix * meanReading);
00092
00093 Matrix result(Matrix::Identity(dimCount, dimCount));
00094 result.topLeftCorner(dimCount-1, dimCount-1) = scale * rotMatrix;
00095 result.topRightCorner(dimCount-1, 1) = trVector;
00096
00097 return result;
00098 }
00099
00100 template<typename T>
00101 T PointToPointSimilarityErrorMinimizer<T>::getResidualError(
00102 const DataPoints& filteredReading,
00103 const DataPoints& filteredReference,
00104 const OutlierWeights& outlierWeights,
00105 const Matches& matches) const
00106 {
00107 assert(matches.ids.rows() > 0);
00108
00109
00110 typename ErrorMinimizer::ErrorElements mPts(filteredReading, filteredReference, outlierWeights, matches);
00111
00112 return PointToPointErrorMinimizer<T>::computeResidualError(mPts);
00113 }
00114
00115 template<typename T>
00116 T PointToPointSimilarityErrorMinimizer<T>::getOverlap() const
00117 {
00118
00119
00120
00121 const int nbPoints = this->lastErrorElements.reading.features.cols();
00122 const int dim = this->lastErrorElements.reading.features.rows();
00123 if(nbPoints == 0)
00124 {
00125 throw std::runtime_error("Error, last error element empty. Error minimizer needs to be called at least once before using this method.");
00126 }
00127
00128 if (!this->lastErrorElements.reading.descriptorExists("simpleSensorNoise"))
00129 {
00130 LOG_INFO_STREAM("PointToPointSimilarityErrorMinimizer - warning, no sensor noise found. Using best estimate given outlier rejection instead.");
00131 return this->getWeightedPointUsedRatio();
00132 }
00133
00134 const BOOST_AUTO(noises, this->lastErrorElements.reading.getDescriptorViewByName("simpleSensorNoise"));
00135
00136 const Vector dists = (this->lastErrorElements.reading.features.topRows(dim-1) - this->lastErrorElements.reference.features.topRows(dim-1)).colwise().norm();
00137 const T mean = dists.sum()/nbPoints;
00138
00139 int count = 0;
00140 for(int i=0; i < nbPoints; i++)
00141 {
00142 if(dists(i) < (mean + noises(0,i)))
00143 {
00144 count++;
00145 }
00146 }
00147
00148 return (T)count/(T)nbPoints;
00149 }
00150
00151 template struct PointToPointSimilarityErrorMinimizer<float>;
00152 template struct PointToPointSimilarityErrorMinimizer<double>;