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 "PointMatcher.h"
00037 #include "PointMatcherPrivate.h"
00038
00040 template<typename T>
00041 PointMatcher<T>::ErrorMinimizer::ErrorMinimizer():
00042 pointUsedRatio(-1.),
00043 weightedPointUsedRatio(-1.)
00044 {}
00045
00047 template<typename T>
00048 PointMatcher<T>::ErrorMinimizer::ErrorMinimizer(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params):
00049 Parametrizable(className,paramsDoc,params)
00050 {}
00051
00053 template<typename T>
00054 PointMatcher<T>::ErrorMinimizer::~ErrorMinimizer()
00055 {}
00056
00058 template<typename T>
00059 PointMatcher<T>::ErrorMinimizer::ErrorElements::ErrorElements(const DataPoints& reading, const DataPoints reference, const OutlierWeights weights, const Matches matches):
00060 reading(reading),
00061 reference(reference),
00062 weights(weights),
00063 matches(matches)
00064 {
00065 assert(reading.features.cols() == reference.features.cols());
00066 assert(reading.features.cols() == weights.cols());
00067 assert(reading.features.cols() == matches.dists.cols());
00068
00069 }
00070
00072 template<typename T>
00073 T PointMatcher<T>::ErrorMinimizer::getPointUsedRatio() const
00074 {
00075 return pointUsedRatio;
00076 }
00077
00079 template<typename T>
00080 T PointMatcher<T>::ErrorMinimizer::getWeightedPointUsedRatio() const
00081 {
00082 return weightedPointUsedRatio;
00083 }
00084
00086 template<typename T>
00087 T PointMatcher<T>::ErrorMinimizer::getOverlap() const
00088 {
00089 LOG_INFO_STREAM("ErrorMinimizer - warning, no specific method to compute overlap was provided for the ErrorMinimizer used.");
00090 return weightedPointUsedRatio;
00091 }
00092
00094 template<typename T>
00095 typename PointMatcher<T>::Matrix PointMatcher<T>::ErrorMinimizer::getCovariance() const
00096 {
00097 LOG_INFO_STREAM("ErrorMinimizer - warning, no specific method to compute covariance was provided for the ErrorMinimizer used.");
00098 return Matrix::Zero(6,6);
00099 }
00100
00102 template<typename T>
00103 typename PointMatcher<T>::Matrix PointMatcher<T>::ErrorMinimizer::crossProduct(const Matrix& A, const Matrix& B)
00104 {
00105
00106
00107
00108 assert(A.cols() == B.cols());
00109
00110
00111 assert(A.rows() -1 == B.rows());
00112
00113
00114 assert(A.rows() == 4 || A.rows() == 3);
00115
00116 const unsigned int x = 0;
00117 const unsigned int y = 1;
00118 const unsigned int z = 2;
00119
00120 Matrix cross;
00121 if(A.rows() == 4)
00122 {
00123 cross = Matrix(B.rows(), B.cols());
00124
00125 cross.row(x) = A.row(y).cwise() * B.row(z) - A.row(z).cwise() * B.row(y);
00126 cross.row(y) = A.row(z).cwise() * B.row(x) - A.row(x).cwise() * B.row(z);
00127 cross.row(z) = A.row(x).cwise() * B.row(y) - A.row(y).cwise() * B.row(x);
00128 }
00129 else
00130 {
00131
00132 cross = Vector(B.cols());
00133 cross = A.row(x).cwise() * B.row(y) - A.row(y).cwise() * B.row(x);
00134 }
00135
00136 return cross;
00137 }
00138
00139
00142 template<typename T>
00143 typename PointMatcher<T>::ErrorMinimizer::ErrorElements& PointMatcher<T>::ErrorMinimizer::getMatchedPoints(
00144 const DataPoints& requestedPts,
00145 const DataPoints& sourcePts,
00146 const Matches& matches,
00147 const OutlierWeights& outlierWeights)
00148 {
00149 typedef typename Matches::Ids Ids;
00150 typedef typename Matches::Dists Dists;
00151
00152 assert(matches.ids.rows() > 0);
00153 assert(matches.ids.cols() > 0);
00154 assert(matches.ids.cols() == requestedPts.features.cols());
00155 assert(outlierWeights.rows() == matches.ids.rows());
00156
00157 const int knn = outlierWeights.rows();
00158 const int dimFeat = requestedPts.features.rows();
00159 const int dimReqDesc = requestedPts.descriptors.rows();
00160
00161
00162 const int pointsCount = (outlierWeights.cwise() != 0.0).count();
00163 if (pointsCount == 0)
00164 throw ConvergenceError("ErrorMnimizer: no point to minimize");
00165
00166 Matrix keptFeat(dimFeat, pointsCount);
00167
00168 Matrix keptDesc;
00169 if(dimReqDesc > 0)
00170 keptDesc = Matrix(dimReqDesc, pointsCount);
00171
00172 Matches keptMatches (Dists(1,pointsCount), Ids(1, pointsCount));
00173 OutlierWeights keptWeights(1, pointsCount);
00174
00175 int j = 0;
00176 weightedPointUsedRatio = 0;
00177 for(int k = 0; k < knn; k++)
00178 {
00179 for (int i = 0; i < requestedPts.features.cols(); ++i)
00180 {
00181 if (outlierWeights(k,i) != 0.0)
00182 {
00183 if(dimReqDesc > 0)
00184 keptDesc.col(j) = requestedPts.descriptors.col(i);
00185
00186 keptFeat.col(j) = requestedPts.features.col(i);
00187 keptMatches.ids(0, j) = matches.ids(k, i);
00188 keptMatches.dists(0, j) = matches.dists(k, i);
00189 keptWeights(0,j) = outlierWeights(k,i);
00190 ++j;
00191 weightedPointUsedRatio += outlierWeights(k,i);
00192 }
00193 }
00194 }
00195
00196 assert(j == pointsCount);
00197
00198 this->pointUsedRatio = double(j)/double(knn*requestedPts.features.cols());
00199 this->weightedPointUsedRatio /= double(knn*requestedPts.features.cols());
00200
00201 assert(dimFeat == sourcePts.features.rows());
00202 const int dimSourDesc = sourcePts.descriptors.rows();
00203
00204 Matrix associatedFeat(dimFeat, pointsCount);
00205 Matrix associatedDesc;
00206 if(dimSourDesc > 0)
00207 associatedDesc = Matrix(dimSourDesc, pointsCount);
00208
00209
00210 for (int i = 0; i < pointsCount; ++i)
00211 {
00212 const int refIndex(keptMatches.ids(i));
00213 associatedFeat.col(i) = sourcePts.features.block(0, refIndex, dimFeat, 1);
00214
00215 if(dimSourDesc > 0)
00216 associatedDesc.col(i) = sourcePts.descriptors.block(0, refIndex, dimSourDesc, 1);
00217 }
00218
00219 lastErrorElements.reading = DataPoints(
00220 keptFeat,
00221 requestedPts.featureLabels,
00222 keptDesc,
00223 requestedPts.descriptorLabels
00224 );
00225 lastErrorElements.reference = DataPoints(
00226 associatedFeat,
00227 sourcePts.featureLabels,
00228 associatedDesc,
00229 sourcePts.descriptorLabels
00230 );
00231 lastErrorElements.weights = keptWeights;
00232 lastErrorElements.matches = keptMatches;
00233 return lastErrorElements;
00234 }
00235
00236 template struct PointMatcher<float>::ErrorMinimizer;
00237 template struct PointMatcher<double>::ErrorMinimizer;