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 "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
00070 transformedCloud.features = parameters * input.features;
00071
00072
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
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
00128
00129
00130
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
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
00173 TransformationParameters correctedParameters(parameters);
00174
00175
00176 correctedParameters.block(0,0,rows-1,cols-1).setIdentity();
00177
00178
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
00192 TransformationParameters parameters_(parameters);
00193
00194
00195 parameters_.block(0,cols-1,rows-1,1).setZero();
00196
00197
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;