ErrorMinimizer.cpp
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2012,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014     * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016     * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00033 
00034 */
00035 
00036 #include "PointMatcher.h"
00037 #include "PointMatcherPrivate.h"
00038 
00040 // ErrorElements
00042 
00044 template<typename T>
00045 PointMatcher<T>::ErrorMinimizer::ErrorElements::ErrorElements():
00046         reading(DataPoints()),
00047         reference(DataPoints()),
00048         weights(OutlierWeights()),
00049         matches(Matches()),
00050         nbRejectedMatches(-1),
00051         nbRejectedPoints(-1),
00052         pointUsedRatio(-1.0),
00053         weightedPointUsedRatio(-1.0)
00054 {
00055 }
00056 
00058 template<typename T>
00059 PointMatcher<T>::ErrorMinimizer::ErrorElements::ErrorElements(const DataPoints& requestedPts, const DataPoints& sourcePts, const OutlierWeights& outlierWeights, const Matches& matches)
00060 {
00061         typedef typename Matches::Ids Ids;
00062         typedef typename Matches::Dists Dists;
00063         
00064         assert(matches.ids.rows() > 0);
00065         assert(matches.ids.cols() > 0);
00066         assert(matches.ids.cols() == requestedPts.features.cols()); //nbpts
00067         assert(outlierWeights.rows() == matches.ids.rows());  // knn
00068         
00069         const int knn = outlierWeights.rows();
00070         const int dimFeat = requestedPts.features.rows();
00071         const int dimReqDesc = requestedPts.descriptors.rows();
00072         const int dimReqTime = requestedPts.times.rows();
00073 
00074         // Count points with no weights
00075         const int pointsCount = (outlierWeights.array() != 0.0).count();
00076         if (pointsCount == 0)
00077                 throw ConvergenceError("ErrorMnimizer: no point to minimize");
00078 
00079         Matrix keptFeat(dimFeat, pointsCount);
00080         
00081         Matrix keptDesc;
00082         if(dimReqDesc > 0)
00083                 keptDesc = Matrix(dimReqDesc, pointsCount);
00084         
00085         Int64Matrix keptTime;
00086         if(dimReqTime > 0)
00087                 keptTime = Int64Matrix(dimReqTime, pointsCount);
00088         
00089         Matches keptMatches (Dists(1,pointsCount), Ids(1, pointsCount));
00090         OutlierWeights keptWeights(1, pointsCount);
00091 
00092         int j = 0;
00093         int rejectedMatchCount = 0;
00094         int rejectedPointCount = 0;
00095         bool matchExist = false;
00096         this->weightedPointUsedRatio = 0;
00097         
00098         for (int i = 0; i < requestedPts.features.cols(); ++i) //nb pts
00099         {
00100                 matchExist = false;
00101                 for(int k = 0; k < knn; k++) // knn
00102                 {
00103                         const auto matchDist = matches.dists(k, i);
00104                         if (matchDist == Matches::InvalidDist){
00105                                 continue;
00106                         }
00107 
00108                         if (outlierWeights(k,i) != 0.0)
00109                         {
00110                                 if(dimReqDesc > 0)
00111                                         keptDesc.col(j) = requestedPts.descriptors.col(i);
00112 
00113                                 if(dimReqTime > 0)
00114                                         keptTime.col(j) = requestedPts.times.col(i);
00115 
00116                                 
00117                                 keptFeat.col(j) = requestedPts.features.col(i);
00118                                 keptMatches.ids(0, j) = matches.ids(k, i);
00119                                 keptMatches.dists(0, j) = matchDist;
00120                                 keptWeights(0,j) = outlierWeights(k,i);
00121                                 ++j;
00122                                 this->weightedPointUsedRatio += outlierWeights(k,i);
00123                                 matchExist = true;
00124                         }
00125                         else
00126                         {
00127                                 rejectedMatchCount++;
00128                         }
00129                 }
00130 
00131                 if(matchExist == false)
00132                 {
00133                         rejectedPointCount++;
00134                 }
00135         }
00136 
00137         assert(j == pointsCount);
00138 
00139         this->pointUsedRatio = T(j)/T(knn*requestedPts.features.cols());
00140         this->weightedPointUsedRatio /= T(knn*requestedPts.features.cols());
00141         
00142         assert(dimFeat == sourcePts.features.rows());
00143         const int dimSourDesc = sourcePts.descriptors.rows();
00144         const int dimSourTime = sourcePts.times.rows();
00145         
00146         Matrix associatedFeat(dimFeat, pointsCount);
00147         
00148         Matrix associatedDesc;
00149         if(dimSourDesc > 0)
00150                 associatedDesc = Matrix(dimSourDesc, pointsCount);
00151         
00152         Int64Matrix associatedTime;
00153         if(dimSourTime> 0)
00154                 associatedTime = Int64Matrix(dimSourTime, pointsCount);
00155         
00156         // Fetch matched points
00157         for (int i = 0; i < pointsCount; ++i)
00158         {
00159                 const int refIndex(keptMatches.ids(i));
00160                 associatedFeat.col(i) = sourcePts.features.block(0, refIndex, dimFeat, 1);
00161                 
00162                 if(dimSourDesc > 0)
00163                         associatedDesc.col(i) = sourcePts.descriptors.block(0, refIndex, dimSourDesc, 1);
00164 
00165                 if(dimSourTime> 0)
00166                         associatedTime.col(i) = sourcePts.times.block(0, refIndex, dimSourTime, 1);
00167 
00168         }
00169 
00170         // Copy final data to structure
00171         this->reading = DataPoints(
00172                 keptFeat, 
00173                 requestedPts.featureLabels,
00174                 keptDesc,
00175                 requestedPts.descriptorLabels,
00176                 keptTime,
00177                 requestedPts.timeLabels
00178         );
00179 
00180         this->reference = DataPoints(
00181                 associatedFeat,
00182                 sourcePts.featureLabels,
00183                 associatedDesc,
00184                 sourcePts.descriptorLabels,
00185                 associatedTime,
00186                 sourcePts.timeLabels
00187         );
00188 
00189         this->weights = keptWeights;
00190         this->matches = keptMatches;
00191         this->nbRejectedMatches = rejectedMatchCount;
00192         this->nbRejectedPoints = rejectedPointCount;
00193 }
00194 
00195 
00197 // ErrorMinimizer
00199 
00201 template<typename T>
00202 PointMatcher<T>::ErrorMinimizer::ErrorMinimizer()
00203 {}
00204 
00206 template<typename T>
00207 PointMatcher<T>::ErrorMinimizer::ErrorMinimizer(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params):
00208         Parametrizable(className,paramsDoc,params)
00209 {}
00210 
00212 template<typename T>
00213 PointMatcher<T>::ErrorMinimizer::~ErrorMinimizer()
00214 {}
00215 
00217 template<typename T>
00218 typename PointMatcher<T>::TransformationParameters PointMatcher<T>::ErrorMinimizer::compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches)
00219 {
00220         
00221         // generates pairs of matching points
00222         typename ErrorMinimizer::ErrorElements matchedPoints(filteredReading, filteredReference, outlierWeights, matches);
00223         
00224         // calls specific instantiation for a given ErrorMinimizer
00225         TransformationParameters transform = this->compute(matchedPoints);
00226         
00227         // saves paired points for future introspection
00228         this->lastErrorElements = matchedPoints;
00229         
00230         // returns transforme parameters
00231         return transform;
00232 }
00233 
00235 template<typename T>
00236 T PointMatcher<T>::ErrorMinimizer::getPointUsedRatio() const
00237 {
00238         return lastErrorElements.pointUsedRatio;
00239 }
00240 
00242 template<typename T>
00243 typename PointMatcher<T>::ErrorMinimizer::ErrorElements PointMatcher<T>::ErrorMinimizer::getErrorElements() const
00244 {
00245         //Warning: the use of the variable lastErrorElements is not standardized yet.
00246         return lastErrorElements;
00247 }
00248 
00250 template<typename T>
00251 T PointMatcher<T>::ErrorMinimizer::getWeightedPointUsedRatio() const
00252 {
00253         return lastErrorElements.weightedPointUsedRatio;
00254 }
00255 
00257 template<typename T>
00258 T PointMatcher<T>::ErrorMinimizer::getOverlap() const
00259 {
00260         LOG_WARNING_STREAM("ErrorMinimizer - warning, no specific method to compute overlap was provided for the ErrorMinimizer used.");
00261         return lastErrorElements.weightedPointUsedRatio;
00262 }
00263 
00265 template<typename T>
00266 typename PointMatcher<T>::Matrix PointMatcher<T>::ErrorMinimizer::getCovariance() const
00267 {
00268         LOG_WARNING_STREAM("ErrorMinimizer - warning, no specific method to compute covariance was provided for the ErrorMinimizer used.");
00269         return Matrix::Zero(6,6);
00270 }
00271 
00273 template<typename T>
00274 T PointMatcher<T>::ErrorMinimizer::getResidualError(const DataPoints& filteredReading, const DataPoints& filteredReference, const OutlierWeights& outlierWeights, const Matches& matches) const
00275 {
00276         LOG_WARNING_STREAM("ErrorMinimizer - warning, no specific method to compute residual was provided for the ErrorMinimizer used.");
00277         return std::numeric_limits<T>::max();
00278 }
00279 
00281 template<typename T>
00282 typename PointMatcher<T>::Matrix PointMatcher<T>::ErrorMinimizer::crossProduct(const Matrix& A, const Matrix& B)
00283 {
00284         //Note: A = [x, y, z, 1] and B = [x, y, z] for convenience
00285 
00286         // Expecting matched points
00287         assert(A.cols() == B.cols());
00288 
00289         // Expecting homogenous coord X eucl. coord
00290         assert(A.rows() -1 == B.rows());
00291 
00292         // Expecting homogenous coordinates
00293         assert(A.rows() == 4 || A.rows() == 3);
00294         
00295         const unsigned int x = 0;
00296         const unsigned int y = 1;
00297         const unsigned int z = 2;
00298 
00299         Matrix cross;
00300         if(A.rows() == 4)
00301         {
00302                 cross = Matrix(B.rows(), B.cols());
00303                                 
00304                 cross.row(x) = A.row(y).array() * B.row(z).array() - A.row(z).array() * B.row(y).array();
00305                 cross.row(y) = A.row(z).array() * B.row(x).array() - A.row(x).array() * B.row(z).array();
00306                 cross.row(z) = A.row(x).array() * B.row(y).array() - A.row(y).array() * B.row(x).array();
00307         }
00308         else
00309         {
00310                 //pseudo-cross product for 2D vectors
00311                 cross = Vector(B.cols());
00312                 cross = A.row(x).array() * B.row(y).array() - A.row(y).array() * B.row(x).array();
00313         }
00314         return cross;
00315 }
00316 
00317 
00318 
00319 
00320 template struct PointMatcher<float>::ErrorMinimizer;
00321 template struct PointMatcher<double>::ErrorMinimizer;


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:29