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 "ErrorMinimizersImpl.h"
00037 #include "PointMatcherPrivate.h"
00038 #include "Eigen/SVD"
00039
00040 using namespace Eigen;
00041
00042 template<typename T>
00043 PointToPointWithCovErrorMinimizer<T>::PointToPointWithCovErrorMinimizer(const Parameters& params):
00044 PointToPointErrorMinimizer<T>("PointToPointWithCovErrorMinimizer", availableParameters(), params),
00045 sensorStdDev(Parametrizable::get<T>("sensorStdDev"))
00046 {
00047 }
00048
00049 template<typename T>
00050 typename PointMatcher<T>::TransformationParameters PointToPointWithCovErrorMinimizer<T>::compute(const ErrorElements& mPts_const)
00051 {
00052 ErrorElements mPts = mPts_const;
00053 typename PointMatcher<T>::TransformationParameters result = PointToPointErrorMinimizer<T>::compute_in_place(mPts);
00054
00055 this->covMatrix = this->estimateCovariance(mPts, result);
00056
00057 return result;
00058 }
00059
00060
00061 template<typename T>
00062 typename PointToPointWithCovErrorMinimizer<T>::Matrix PointToPointWithCovErrorMinimizer<T>::estimateCovariance(const ErrorElements& mPts, const TransformationParameters& transformation)
00063 {
00064 const int max_nbr_point = mPts.reading.getNbPoints();
00065
00066 Matrix covariance(Matrix::Zero(6,6));
00067 Matrix J_hessian(Matrix::Zero(6,6));
00068 Matrix d2J_dReadingdX(Matrix::Zero(6, max_nbr_point));
00069 Matrix d2J_dReferencedX(Matrix::Zero(6, max_nbr_point));
00070
00071 Vector reading_point(Vector::Zero(3));
00072 Vector reference_point(Vector::Zero(3));
00073 Vector normal(3);
00074 Vector reading_direction(Vector::Zero(3));
00075 Vector reference_direction(Vector::Zero(3));
00076
00077 normal << 1.0, 1.0, 1.0;
00078
00079 T beta = -asin(transformation(2,0));
00080 T alpha = atan2(transformation(2,1), transformation(2,2));
00081 T gamma = atan2(transformation(1,0)/cos(beta), transformation(0,0)/cos(beta));
00082 T t_x = transformation(0,3);
00083 T t_y = transformation(1,3);
00084 T t_z = transformation(2,3);
00085
00086 Vector tmp_vector_6(Vector::Zero(6));
00087
00088 int valid_points_count = 0;
00089
00090
00091 for(int i = 0; i < max_nbr_point; ++i)
00092 {
00093
00094 {
00095 reading_point = mPts.reading.features.block(0,i,3,1);
00096
00097 reference_point = mPts.reference.features.block(0,i,3,1);
00098
00099 T reading_range = reading_point.norm();
00100 reading_direction = reading_point / reading_range;
00101 T reference_range = reference_point.norm();
00102 reference_direction = reference_point / reference_range;
00103
00104 T n_alpha = normal(2)*reading_direction(1) - normal(1)*reading_direction(2);
00105 T n_beta = normal(0)*reading_direction(2) - normal(2)*reading_direction(0);
00106 T n_gamma = normal(1)*reading_direction(0) - normal(0)*reading_direction(1);
00107
00108 T E = normal(0)*(reading_point(0) - gamma*reading_point(1) + beta*reading_point(2) + t_x - reference_point(0));
00109 E += normal(1)*(gamma*reading_point(0) + reading_point(1) - alpha*reading_point(2) + t_y - reference_point(1));
00110 E += normal(2)*(-beta*reading_point(0) + alpha*reading_point(1) + reading_point(2) + t_z - reference_point(2));
00111
00112 T N_reading = normal(0)*(reading_direction(0) - gamma*reading_direction(1) + beta*reading_direction(2));
00113 N_reading += normal(1)*(gamma*reading_direction(0) + reading_direction(1) - alpha*reading_direction(2));
00114 N_reading += normal(2)*(-beta*reading_direction(0) + alpha*reading_direction(1) + reading_direction(2));
00115
00116 T N_reference = -(normal(0)*reference_direction(0) + normal(1)*reference_direction(1) + normal(2)*reference_direction(2));
00117
00118
00119 tmp_vector_6 << normal(0), normal(1), normal(2), reading_range * n_alpha, reading_range * n_beta, reading_range * n_gamma;
00120
00121 J_hessian += tmp_vector_6 * tmp_vector_6.transpose();
00122
00123 tmp_vector_6 << normal(0) * N_reading, normal(1) * N_reading, normal(2) * N_reading, n_alpha * (E + reading_range * N_reading), n_beta * (E + reading_range * N_reading), n_gamma * (E + reading_range * N_reading);
00124
00125 d2J_dReadingdX.block(0,valid_points_count,6,1) = tmp_vector_6;
00126
00127 tmp_vector_6 << normal(0) * N_reference, normal(1) * N_reference, normal(2) * N_reference, reference_range * n_alpha * N_reference, reference_range * n_beta * N_reference, reference_range * n_gamma * N_reference;
00128
00129 d2J_dReferencedX.block(0,valid_points_count,6,1) = tmp_vector_6;
00130
00131 valid_points_count++;
00132 }
00133 }
00134
00135 Matrix d2J_dZdX(Matrix::Zero(6, 2 * valid_points_count));
00136 d2J_dZdX.block(0,0,6,valid_points_count) = d2J_dReadingdX.block(0,0,6,valid_points_count);
00137 d2J_dZdX.block(0,valid_points_count,6,valid_points_count) = d2J_dReferencedX.block(0,0,6,valid_points_count);
00138
00139 Matrix inv_J_hessian = J_hessian.inverse();
00140
00141 covariance = d2J_dZdX * d2J_dZdX.transpose();
00142 covariance = inv_J_hessian * covariance * inv_J_hessian;
00143
00144 return (sensorStdDev * sensorStdDev) * covariance;
00145 }
00146
00147 template<typename T>
00148 typename PointToPointWithCovErrorMinimizer<T>::Matrix PointToPointWithCovErrorMinimizer<T>::getCovariance() const
00149 {
00150 return covMatrix;
00151 }
00152
00153 template struct PointToPointWithCovErrorMinimizer<float>;
00154 template struct PointToPointWithCovErrorMinimizer<double>;