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 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::crossProduct(const Matrix& A, const Matrix& B)
00096 {
00097     //Note: A = [x, y, z, 1] and B = [x, y, z] for convenience
00098 
00099     // Expecting matched points
00100     assert(A.cols() == B.cols());
00101 
00102     // Expecting homogenous coord X eucl. coord
00103     assert(A.rows() -1 == B.rows());
00104 
00105     // Expecting homogenous coordinates
00106     assert(A.rows() == 4 || A.rows() == 3);
00107     
00108     const unsigned int x = 0;
00109     const unsigned int y = 1;
00110     const unsigned int z = 2;
00111 
00112     Matrix cross;
00113     if(A.rows() == 4)
00114     {
00115         cross = Matrix(B.rows(), B.cols());
00116                 
00117         cross.row(x) = A.row(y).cwise() * B.row(z) - A.row(z).cwise() * B.row(y);
00118         cross.row(y) = A.row(z).cwise() * B.row(x) - A.row(x).cwise() * B.row(z);
00119         cross.row(z) = A.row(x).cwise() * B.row(y) - A.row(y).cwise() * B.row(x);
00120     }
00121     else
00122     {
00123         //pseudo-cross product for 2D vectors
00124         cross = Vector(B.cols());
00125         cross = A.row(x).cwise() * B.row(y) - A.row(y).cwise() * B.row(x);
00126     }
00127 
00128     return cross;
00129 }
00130 
00131 
00134 template<typename T>
00135 typename PointMatcher<T>::ErrorMinimizer::ErrorElements& PointMatcher<T>::ErrorMinimizer::getMatchedPoints(
00136         const DataPoints& requestedPts,
00137         const DataPoints& sourcePts,
00138         const Matches& matches, 
00139         const OutlierWeights& outlierWeights)
00140 {
00141     typedef typename Matches::Ids Ids;
00142     typedef typename Matches::Dists Dists;
00143     
00144     assert(matches.ids.rows() > 0);
00145     assert(matches.ids.cols() > 0);
00146     assert(matches.ids.cols() == requestedPts.features.cols()); //nbpts
00147     assert(outlierWeights.rows() == matches.ids.rows());  // knn
00148     
00149     const int knn = outlierWeights.rows();
00150     const int dimFeat = requestedPts.features.rows();
00151     const int dimReqDesc = requestedPts.descriptors.rows();
00152 
00153     // Count points with no weights
00154     const int pointsCount = (outlierWeights.cwise() != 0.0).count();
00155     if (pointsCount == 0)
00156         throw ConvergenceError("ErrorMnimizer: no point to minimize");
00157 
00158     Matrix keptFeat(dimFeat, pointsCount);
00159     
00160     Matrix keptDesc;
00161     if(dimReqDesc > 0)
00162         keptDesc = Matrix(dimReqDesc, pointsCount);
00163 
00164     Matches keptMatches (Dists(1,pointsCount), Ids(1, pointsCount));
00165     OutlierWeights keptWeights(1, pointsCount);
00166 
00167     int j = 0;
00168     weightedPointUsedRatio = 0;
00169     for(int k = 0; k < knn; k++) // knn
00170     {
00171         for (int i = 0; i < requestedPts.features.cols(); ++i) //nb pts
00172         {
00173             if (outlierWeights(k,i) != 0.0)
00174             {
00175                 if(dimReqDesc > 0)
00176                     keptDesc.col(j) = requestedPts.descriptors.col(i);
00177                 
00178                 keptFeat.col(j) = requestedPts.features.col(i);
00179                 keptMatches.ids(0, j) = matches.ids(k, i);
00180                 keptMatches.dists(0, j) = matches.dists(k, i);
00181                 keptWeights(0,j) = outlierWeights(k,i);
00182                 ++j;
00183                 weightedPointUsedRatio += outlierWeights(k,i);
00184             }
00185         }
00186     }
00187 
00188     assert(j == pointsCount);
00189 
00190     this->pointUsedRatio = double(j)/double(knn*requestedPts.features.cols());
00191     this->weightedPointUsedRatio /= double(knn*requestedPts.features.cols());
00192     
00193     assert(dimFeat == sourcePts.features.rows());
00194     const int dimSourDesc = sourcePts.descriptors.rows();
00195     
00196     Matrix associatedFeat(dimFeat, pointsCount);
00197     Matrix associatedDesc;
00198     if(dimSourDesc > 0)
00199         associatedDesc = Matrix(dimSourDesc, pointsCount);
00200 
00201     // Fetch matched points
00202     for (int i = 0; i < pointsCount; ++i)
00203     {
00204         const int refIndex(keptMatches.ids(i));
00205         associatedFeat.col(i) = sourcePts.features.block(0, refIndex, dimFeat, 1);
00206         
00207         if(dimSourDesc > 0)
00208             associatedDesc.col(i) = sourcePts.descriptors.block(0, refIndex, dimSourDesc, 1);
00209     }
00210 
00211     lastErrorElements.reading = DataPoints(
00212         keptFeat, 
00213         requestedPts.featureLabels,
00214         keptDesc,
00215         requestedPts.descriptorLabels
00216     );
00217     lastErrorElements.reference = DataPoints(
00218         associatedFeat,
00219         sourcePts.featureLabels,
00220         associatedDesc,
00221         sourcePts.descriptorLabels
00222     );
00223     lastErrorElements.weights = keptWeights;
00224     lastErrorElements.matches = keptMatches;
00225     return lastErrorElements;
00226 }
00227 
00228 template struct PointMatcher<float>::ErrorMinimizer;
00229 template struct PointMatcher<double>::ErrorMinimizer;


libpointmatcher
Author(s): Stéphane Magnenat, François Pomerleau
autogenerated on Thu Jan 2 2014 11:16:06