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 PointToPointErrorMinimizer<T>::PointToPointErrorMinimizer() :
00044 PointMatcher<T>::ErrorMinimizer("PointToPointErrorMinimizer",
00045 ParametersDoc(),
00046 Parameters()) {}
00047
00048 template<typename T>
00049 PointToPointErrorMinimizer<T>::PointToPointErrorMinimizer(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params):
00050 ErrorMinimizer(className, paramsDoc, params)
00051 {
00052 }
00053
00054 template<typename T>
00055 typename PointMatcher<T>::TransformationParameters PointToPointErrorMinimizer<T>::compute(const ErrorElements& mPts_const)
00056 {
00057 ErrorElements mPts = mPts_const;
00058 return compute_in_place(mPts);
00059 }
00060
00061 template<typename T>
00062 typename PointMatcher<T>::TransformationParameters PointToPointErrorMinimizer<T>::compute_in_place(ErrorElements& mPts) {
00063 const int dimCount(mPts.reading.features.rows());
00064
00065
00066
00067 const Vector w = mPts.weights.row(0);
00068 const T w_sum_inv = T(1.)/w.sum();
00069 const Vector meanReading =
00070 (mPts.reading.features.topRows(dimCount-1).array().rowwise() * w.array().transpose()).rowwise().sum() * w_sum_inv;
00071 const Vector meanReference =
00072 (mPts.reference.features.topRows(dimCount-1).array().rowwise() * w.array().transpose()).rowwise().sum() * w_sum_inv;
00073
00074
00075
00076 mPts.reading.features.topRows(dimCount-1).colwise() -= meanReading;
00077 mPts.reference.features.topRows(dimCount-1).colwise() -= meanReference;
00078
00079
00080 const Matrix m(mPts.reference.features.topRows(dimCount-1) * w.asDiagonal()
00081 * mPts.reading.features.topRows(dimCount-1).transpose());
00082 const JacobiSVD<Matrix> svd(m, ComputeThinU | ComputeThinV);
00083 Matrix rotMatrix(svd.matrixU() * svd.matrixV().transpose());
00084
00085
00086
00087
00088 if (rotMatrix.determinant() < 0.)
00089 {
00090 Matrix tmpV = svd.matrixV().transpose();
00091 tmpV.row(dimCount-2) *= -1.;
00092 rotMatrix = svd.matrixU() * tmpV;
00093 }
00094 const Vector trVector(meanReference - rotMatrix * meanReading);
00095
00096 Matrix result(Matrix::Identity(dimCount, dimCount));
00097 result.topLeftCorner(dimCount-1, dimCount-1) = rotMatrix;
00098 result.topRightCorner(dimCount-1, 1) = trVector;
00099
00100 return result;
00101 }
00102
00103 template<typename T>
00104 T PointToPointErrorMinimizer<T>::getResidualError(
00105 const DataPoints& filteredReading,
00106 const DataPoints& filteredReference,
00107 const OutlierWeights& outlierWeights,
00108 const Matches& matches) const
00109 {
00110 assert(matches.ids.rows() > 0);
00111
00112
00113 typename ErrorMinimizer::ErrorElements mPts(filteredReading, filteredReference, outlierWeights, matches);
00114
00115 return PointToPointErrorMinimizer::computeResidualError(mPts);
00116 }
00117
00118 template<typename T>
00119 T PointToPointErrorMinimizer<T>::getOverlap() const
00120 {
00121
00122
00123
00124 const int nbPoints = this->lastErrorElements.reading.features.cols();
00125 const int dim = this->lastErrorElements.reading.features.rows();
00126 if(nbPoints == 0)
00127 {
00128 throw std::runtime_error("Error, last error element empty. Error minimizer needs to be called at least once before using this method.");
00129 }
00130
00131 if (!this->lastErrorElements.reading.descriptorExists("simpleSensorNoise"))
00132 {
00133 LOG_INFO_STREAM("PointToPointErrorMinimizer - warning, no sensor noise found. Using best estimate given outlier rejection instead.");
00134 return this->getWeightedPointUsedRatio();
00135 }
00136
00137 const BOOST_AUTO(noises, this->lastErrorElements.reading.getDescriptorViewByName("simpleSensorNoise"));
00138
00139 const Vector dists = (this->lastErrorElements.reading.features.topRows(dim-1) - this->lastErrorElements.reference.features.topRows(dim-1)).colwise().norm();
00140 const T mean = dists.sum()/nbPoints;
00141
00142 int count = 0;
00143 for(int i=0; i < nbPoints; i++)
00144 {
00145 if(dists(i) < (mean + noises(0,i)))
00146 {
00147 count++;
00148 }
00149 }
00150
00151 return (T)count/(T)nbPoints;
00152 }
00153
00154 template<typename T>
00155 T PointToPointErrorMinimizer<T>::computeResidualError(const ErrorElements& mPts)
00156 {
00157
00158
00159 const Matrix deltas = mPts.reading.features - mPts.reference.features;
00160
00161
00162 Matrix deltaNorms = deltas.colwise().norm();
00163 return deltaNorms.sum();
00164 }
00165
00166 template struct PointToPointErrorMinimizer<float>;
00167 template struct PointToPointErrorMinimizer<double>;