TransformationsImpl.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 "TransformationsImpl.h"
00037 #include "Functions.h"
00038 
00039 #include <iostream>
00040 
00041 using namespace PointMatcherSupport;
00042 
00044 TransformationError::TransformationError(const std::string& reason):
00045         runtime_error(reason)
00046 {}
00047 
00049 template<typename T>
00050 typename PointMatcher<T>::DataPoints TransformationsImpl<T>::RigidTransformation::compute(
00051         const DataPoints& input,
00052         const TransformationParameters& parameters) const
00053 {
00054         typedef typename PointMatcher<T>::Matrix Matrix;
00055         
00056         assert(input.features.rows() == parameters.rows());
00057         assert(parameters.rows() == parameters.cols());
00058 
00059         const unsigned int nbRows = parameters.rows()-1;
00060         const unsigned int nbCols = parameters.cols()-1;
00061 
00062         const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols));
00063 
00064         if(this->checkParameters(parameters) == false)  
00065                 throw TransformationError("RigidTransformation: Error, rotation matrix is not orthogonal.");    
00066         
00067         DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.features.cols());
00068         
00069         // Apply the transformation to features
00070         transformedCloud.features = parameters * input.features;
00071         
00072         // Apply the transformation to descriptors
00073         int row(0);
00074         const int descCols(input.descriptors.cols());
00075         for (size_t i = 0; i < input.descriptorLabels.size(); ++i)
00076         {
00077                 const int span(input.descriptorLabels[i].span);
00078                 const std::string& name(input.descriptorLabels[i].text);
00079                 const BOOST_AUTO(inputDesc, input.descriptors.block(row, 0, span, descCols));
00080                 BOOST_AUTO(outputDesc, transformedCloud.descriptors.block(row, 0, span, descCols));
00081                 if (name == "normals" || name == "observationDirections")
00082                         outputDesc = R * inputDesc;
00083                 else
00084                         outputDesc = inputDesc;
00085                 row += span;
00086         }
00087         
00088         return transformedCloud;
00089 }
00090 
00092 template<typename T>
00093 bool TransformationsImpl<T>::RigidTransformation::checkParameters(const TransformationParameters& parameters) const
00094 {
00095         //FIXME: FP - should we put that as function argument?
00096         const T epsilon = 0.001;
00097         const unsigned int nbRows = parameters.rows()-1;
00098         const unsigned int nbCols = parameters.cols()-1;
00099 
00100         const TransformationParameters R(parameters.topLeftCorner(nbRows, nbCols));
00101         
00102         if(anyabs(1 - R.determinant()) > epsilon)
00103                 return false;
00104         else
00105                 return true;
00106 
00107 }
00108 
00110 template<typename T>
00111 typename PointMatcher<T>::TransformationParameters TransformationsImpl<T>::RigidTransformation::correctParameters(const TransformationParameters& parameters) const
00112 {
00113         TransformationParameters ortho = parameters;
00114         if(ortho.cols() == 4)
00115         {
00116                 const Eigen::Matrix<T, 3, 1> col0 = parameters.block(0, 0, 3, 1).normalized();
00117                 const Eigen::Matrix<T, 3, 1> col1 = parameters.block(0, 1, 3, 1).normalized();
00118                 const Eigen::Matrix<T, 3, 1> col2 = parameters.block(0, 2, 3, 1).normalized();
00119 
00120 
00121                 ortho.block(0, 0, 3, 1) = col1.cross(col2);
00122                 ortho.block(0, 1, 3, 1) = col2.cross(col0);
00123                 ortho.block(0, 2, 3, 1) = col2;
00124         }
00125         else if(ortho.cols() == 3)
00126         {
00127                 // R = [ a b]
00128                 //     [-b a]
00129                 
00130                 // mean of a and b
00131                 T a = (parameters(0,0) + parameters(1,1))/2;    
00132                 T b = (-parameters(1,0) + parameters(0,1))/2;
00133                 T sum = sqrt(pow(a,2) + pow(b,2));
00134 
00135                 a = a/sum;
00136                 b = b/sum;
00137 
00138                 ortho(0,0) =  a; ortho(0,1) = b;
00139                 ortho(1,0) = -b; ortho(1,1) = a;
00140         }
00141 
00142 
00143         return ortho;
00144 }
00145 
00146 template struct TransformationsImpl<float>::RigidTransformation;
00147 template struct TransformationsImpl<double>::RigidTransformation;
00148 
00149 template<typename T>
00150 typename PointMatcher<T>::DataPoints TransformationsImpl<T>::PureTranslation::compute(const DataPoints& input,
00151                 const TransformationParameters& parameters) const {
00152         assert(input.features.rows() == parameters.rows());
00153         assert(parameters.rows() == parameters.cols());
00154 
00155         if(this->checkParameters(parameters) == false)
00156                 throw PointMatcherSupport::TransformationError("PureTranslation: Error, left part  not identity.");
00157 
00158         DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.features.cols());
00159 
00160         // Apply the transformation to features
00161         transformedCloud.features = parameters * input.features;
00162 
00163         return transformedCloud;
00164 }
00165 
00166 template<typename T>
00167 typename PointMatcher<T>::TransformationParameters TransformationsImpl<T>::PureTranslation::correctParameters(
00168                 const TransformationParameters& parameters) const {
00169         const int rows = parameters.rows();
00170         const int cols = parameters.cols();
00171 
00172         // make a copy of the parameters to perform corrections on
00173         TransformationParameters correctedParameters(parameters);
00174 
00175         // set the top left block to the identity matrix
00176         correctedParameters.block(0,0,rows-1,cols-1).setIdentity();
00177 
00178         // fix the bottom row
00179         correctedParameters.block(rows-1,0,1,cols-1).setZero();
00180         correctedParameters(rows-1,cols-1) = 1;
00181 
00182         return correctedParameters;
00183 }
00184 
00185 template<typename T>
00186 bool TransformationsImpl<T>::PureTranslation::checkParameters(
00187                 const TransformationParameters& parameters) const {
00188         const int rows = parameters.rows();
00189         const int cols = parameters.cols();
00190 
00191         // make a copy of parameters to perform the check
00192         TransformationParameters parameters_(parameters);
00193 
00194         // set the translation components of the transformation matrix to 0
00195         parameters_.block(0,cols-1,rows-1,1).setZero();
00196 
00197         // If we have the identity matrix, than this is indeed a pure translation
00198         if (parameters_.isApprox(TransformationParameters::Identity(rows,cols)))
00199                 return true;
00200         else
00201                 return false;
00202 }
00203 
00204 template struct TransformationsImpl<float>::PureTranslation;
00205 template struct TransformationsImpl<double>::PureTranslation;


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