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 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         // May have no descriptors... size 0
00069 }
00070 
00072 template<typename T>
00073 T PointMatcher<T>::ErrorMinimizer::getPointUsedRatio() const
00074 {
00075         return pointUsedRatio;
00076 }
00077 
00079 template<typename T>
00080 typename PointMatcher<T>::ErrorMinimizer::ErrorElements PointMatcher<T>::ErrorMinimizer::getErrorElements() const
00081 {
00082         //Warning: the use of the variable lastErrorElements is not standardized yet.
00083         return lastErrorElements;
00084 }
00085 
00087 template<typename T>
00088 T PointMatcher<T>::ErrorMinimizer::getWeightedPointUsedRatio() const
00089 {
00090         return weightedPointUsedRatio;
00091 }
00092 
00094 template<typename T>
00095 T PointMatcher<T>::ErrorMinimizer::getOverlap() const
00096 {
00097         LOG_INFO_STREAM("ErrorMinimizer - warning, no specific method to compute overlap was provided for the ErrorMinimizer used.");
00098         return weightedPointUsedRatio;
00099 }
00100 
00102 template<typename T>
00103 typename PointMatcher<T>::Matrix PointMatcher<T>::ErrorMinimizer::getCovariance() const
00104 {
00105   LOG_INFO_STREAM("ErrorMinimizer - warning, no specific method to compute covariance was provided for the ErrorMinimizer used.");
00106   return Matrix::Zero(6,6);
00107 }
00108 
00110 template<typename T>
00111 typename PointMatcher<T>::Matrix PointMatcher<T>::ErrorMinimizer::crossProduct(const Matrix& A, const Matrix& B)
00112 {
00113         //Note: A = [x, y, z, 1] and B = [x, y, z] for convenience
00114 
00115         // Expecting matched points
00116         assert(A.cols() == B.cols());
00117 
00118         // Expecting homogenous coord X eucl. coord
00119         assert(A.rows() -1 == B.rows());
00120 
00121         // Expecting homogenous coordinates
00122         assert(A.rows() == 4 || A.rows() == 3);
00123         
00124         const unsigned int x = 0;
00125         const unsigned int y = 1;
00126         const unsigned int z = 2;
00127 
00128         Matrix cross;
00129         if(A.rows() == 4)
00130         {
00131                 cross = Matrix(B.rows(), B.cols());
00132                                 
00133                 cross.row(x) = A.row(y).array() * B.row(z).array() - A.row(z).array() * B.row(y).array();
00134                 cross.row(y) = A.row(z).array() * B.row(x).array() - A.row(x).array() * B.row(z).array();
00135                 cross.row(z) = A.row(x).array() * B.row(y).array() - A.row(y).array() * B.row(x).array();
00136         }
00137         else
00138         {
00139                 //pseudo-cross product for 2D vectors
00140                 cross = Vector(B.cols());
00141                 cross = A.row(x).array() * B.row(y).array() - A.row(y).array() * B.row(x).array();
00142         }
00143         return cross;
00144 }
00145 
00146 
00149 template<typename T>
00150 typename PointMatcher<T>::ErrorMinimizer::ErrorElements& PointMatcher<T>::ErrorMinimizer::getMatchedPoints(
00151                 const DataPoints& requestedPts,
00152                 const DataPoints& sourcePts,
00153                 const Matches& matches, 
00154                 const OutlierWeights& outlierWeights)
00155 {
00156         typedef typename Matches::Ids Ids;
00157         typedef typename Matches::Dists Dists;
00158         
00159         assert(matches.ids.rows() > 0);
00160         assert(matches.ids.cols() > 0);
00161         assert(matches.ids.cols() == requestedPts.features.cols()); //nbpts
00162         assert(outlierWeights.rows() == matches.ids.rows());  // knn
00163         
00164         const int knn = outlierWeights.rows();
00165         const int dimFeat = requestedPts.features.rows();
00166         const int dimReqDesc = requestedPts.descriptors.rows();
00167 
00168         // Count points with no weights
00169         const int pointsCount = (outlierWeights.array() != 0.0).count();
00170         if (pointsCount == 0)
00171                 throw ConvergenceError("ErrorMnimizer: no point to minimize");
00172 
00173         Matrix keptFeat(dimFeat, pointsCount);
00174         
00175         Matrix keptDesc;
00176         if(dimReqDesc > 0)
00177                 keptDesc = Matrix(dimReqDesc, pointsCount);
00178 
00179         Matches keptMatches (Dists(1,pointsCount), Ids(1, pointsCount));
00180         OutlierWeights keptWeights(1, pointsCount);
00181 
00182         int j = 0;
00183         weightedPointUsedRatio = 0;
00184         for(int k = 0; k < knn; k++) // knn
00185         {
00186                 for (int i = 0; i < requestedPts.features.cols(); ++i) //nb pts
00187                 {
00188                         if (outlierWeights(k,i) != 0.0)
00189                         {
00190                                 if(dimReqDesc > 0)
00191                                         keptDesc.col(j) = requestedPts.descriptors.col(i);
00192                                 
00193                                 keptFeat.col(j) = requestedPts.features.col(i);
00194                                 keptMatches.ids(0, j) = matches.ids(k, i);
00195                                 keptMatches.dists(0, j) = matches.dists(k, i);
00196                                 keptWeights(0,j) = outlierWeights(k,i);
00197                                 ++j;
00198                                 weightedPointUsedRatio += outlierWeights(k,i);
00199                         }
00200                 }
00201         }
00202 
00203         assert(j == pointsCount);
00204 
00205         this->pointUsedRatio = double(j)/double(knn*requestedPts.features.cols());
00206         this->weightedPointUsedRatio /= double(knn*requestedPts.features.cols());
00207         
00208         assert(dimFeat == sourcePts.features.rows());
00209         const int dimSourDesc = sourcePts.descriptors.rows();
00210         
00211         Matrix associatedFeat(dimFeat, pointsCount);
00212         Matrix associatedDesc;
00213         if(dimSourDesc > 0)
00214                 associatedDesc = Matrix(dimSourDesc, pointsCount);
00215 
00216         // Fetch matched points
00217         for (int i = 0; i < pointsCount; ++i)
00218         {
00219                 const int refIndex(keptMatches.ids(i));
00220                 associatedFeat.col(i) = sourcePts.features.block(0, refIndex, dimFeat, 1);
00221                 
00222                 if(dimSourDesc > 0)
00223                         associatedDesc.col(i) = sourcePts.descriptors.block(0, refIndex, dimSourDesc, 1);
00224         }
00225 
00226         lastErrorElements.reading = DataPoints(
00227                 keptFeat, 
00228                 requestedPts.featureLabels,
00229                 keptDesc,
00230                 requestedPts.descriptorLabels
00231         );
00232         lastErrorElements.reference = DataPoints(
00233                 associatedFeat,
00234                 sourcePts.featureLabels,
00235                 associatedDesc,
00236                 sourcePts.descriptorLabels
00237         );
00238         lastErrorElements.weights = keptWeights;
00239         lastErrorElements.matches = keptMatches;
00240         return lastErrorElements;
00241 }
00242 
00243 template struct PointMatcher<float>::ErrorMinimizer;
00244 template struct PointMatcher<double>::ErrorMinimizer;


libpointmatcher
Author(s):
autogenerated on Mon Sep 14 2015 02:59:04