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
00055
00056 assert(input.features.rows() == parameters.rows());
00057 assert(parameters.rows() == parameters.cols());
00058
00059 const TransformationParameters R(parameters.topLeftCorner(parameters.rows()-1, parameters.cols()-1));
00060
00061 if(this->checkParameters(parameters) == false)
00062 throw TransformationError("RigidTransformation: Error, rotation matrix is not orthogonal.");
00063
00064 DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.features.cols());
00065
00066
00067 transformedCloud.features = parameters * input.features;
00068
00069
00070 int row(0);
00071 const int descCols(input.descriptors.cols());
00072 for (size_t i = 0; i < input.descriptorLabels.size(); ++i)
00073 {
00074 const int span(input.descriptorLabels[i].span);
00075 const std::string& name(input.descriptorLabels[i].text);
00076 const BOOST_AUTO(inputDesc, input.descriptors.block(row, 0, span, descCols));
00077 BOOST_AUTO(outputDesc, transformedCloud.descriptors.block(row, 0, span, descCols));
00078 if (name == "normals" || name == "observationDirections")
00079 outputDesc = R * inputDesc;
00080 else
00081 outputDesc = inputDesc;
00082 row += span;
00083 }
00084
00085 return transformedCloud;
00086 }
00087
00089 template<typename T>
00090 bool TransformationsImpl<T>::RigidTransformation::checkParameters(const TransformationParameters& parameters) const
00091 {
00092
00093 const T epsilon = 0.001;
00094
00095 const TransformationParameters R(parameters.topLeftCorner(parameters.rows()-1, parameters.cols()-1));
00096
00097 if(anyabs(1 - R.determinant()) > epsilon)
00098 return false;
00099 else
00100 return true;
00101 }
00102
00104 template<typename T>
00105 typename PointMatcher<T>::TransformationParameters TransformationsImpl<T>::RigidTransformation::correctParameters(const TransformationParameters& parameters) const
00106 {
00107 TransformationParameters ortho = parameters;
00108 if(ortho.cols() == 4)
00109 {
00110 const Eigen::Matrix<T, 3, 1> col0 = parameters.block(0, 0, 3, 1).normalized();
00111 const Eigen::Matrix<T, 3, 1> col1 = parameters.block(0, 1, 3, 1).normalized();
00112 const Eigen::Matrix<T, 3, 1> col2 = parameters.block(0, 2, 3, 1).normalized();
00113
00114
00115 ortho.block(0, 0, 3, 1) = col1.cross(col2);
00116 ortho.block(0, 1, 3, 1) = col2.cross(col0);
00117 ortho.block(0, 2, 3, 1) = col2;
00118 }
00119 else if(ortho.cols() == 3)
00120 {
00121
00122
00123
00124
00125 T a = (parameters(0,0) + parameters(1,1))/2;
00126 T b = (-parameters(1,0) + parameters(0,1))/2;
00127 T sum = sqrt(pow(a,2) + pow(b,2));
00128
00129 a = a/sum;
00130 b = b/sum;
00131
00132 ortho(0,0) = a; ortho(0,1) = b;
00133 ortho(1,0) = -b; ortho(1,1) = a;
00134 }
00135
00136
00137 return ortho;
00138 }
00139
00140 template struct TransformationsImpl<float>::RigidTransformation;
00141 template struct TransformationsImpl<double>::RigidTransformation;
00142
00143 template<typename T>
00144 typename PointMatcher<T>::DataPoints TransformationsImpl<T>::PureTranslation::compute(const DataPoints& input,
00145 const TransformationParameters& parameters) const {
00146 assert(input.features.rows() == parameters.rows());
00147 assert(parameters.rows() == parameters.cols());
00148
00149 if(this->checkParameters(parameters) == false)
00150 throw PointMatcherSupport::TransformationError("PureTranslation: Error, left part not identity.");
00151
00152 DataPoints transformedCloud(input.featureLabels, input.descriptorLabels, input.features.cols());
00153
00154
00155 transformedCloud.features = parameters * input.features;
00156
00157 return transformedCloud;
00158 }
00159
00160 template<typename T>
00161 typename PointMatcher<T>::TransformationParameters TransformationsImpl<T>::PureTranslation::correctParameters(
00162 const TransformationParameters& parameters) const {
00163 const int rows = parameters.rows();
00164 const int cols = parameters.cols();
00165
00166
00167 TransformationParameters correctedParameters(parameters);
00168
00169
00170 correctedParameters.block(0,0,rows-1,cols-1).setIdentity();
00171
00172
00173 correctedParameters.block(rows-1,0,1,cols-1).setZero();
00174 correctedParameters(rows-1,cols-1) = 1;
00175
00176 return correctedParameters;
00177 }
00178
00179 template<typename T>
00180 bool TransformationsImpl<T>::PureTranslation::checkParameters(
00181 const TransformationParameters& parameters) const {
00182 const int rows = parameters.rows();
00183 const int cols = parameters.cols();
00184
00185
00186 TransformationParameters parameters_(parameters);
00187
00188
00189 parameters_.block(0,cols-1,rows-1,1).setZero();
00190
00191
00192 if (parameters_.isApprox(TransformationParameters::Identity(rows,cols)))
00193 return true;
00194 else
00195 return false;
00196 }
00197
00198 template struct TransformationsImpl<float>::PureTranslation;
00199 template struct TransformationsImpl<double>::PureTranslation;