40 using namespace Eigen;
66 Matrix covariance(Matrix::Zero(6,6));
67 Matrix J_hessian(Matrix::Zero(6,6));
68 Matrix d2J_dReadingdX(Matrix::Zero(6, max_nbr_point));
69 Matrix d2J_dReferencedX(Matrix::Zero(6, max_nbr_point));
71 Vector reading_point(Vector::Zero(3));
72 Vector reference_point(Vector::Zero(3));
74 Vector reading_direction(Vector::Zero(3));
75 Vector reference_direction(Vector::Zero(3));
77 normal << 1.0, 1.0, 1.0;
86 Vector tmp_vector_6(Vector::Zero(6));
88 int valid_points_count = 0;
91 for(
int i = 0; i < max_nbr_point; ++i)
99 T reading_range = reading_point.norm();
100 reading_direction = reading_point / reading_range;
101 T reference_range = reference_point.norm();
102 reference_direction = reference_point / reference_range;
104 T n_alpha = normal(2)*reading_direction(1) - normal(1)*reading_direction(2);
105 T n_beta = normal(0)*reading_direction(2) - normal(2)*reading_direction(0);
106 T n_gamma = normal(1)*reading_direction(0) - normal(0)*reading_direction(1);
108 T E = normal(0)*(reading_point(0) - gamma*reading_point(1) + beta*reading_point(2) + t_x - reference_point(0));
109 E += normal(1)*(gamma*reading_point(0) + reading_point(1) - alpha*reading_point(2) + t_y - reference_point(1));
110 E += normal(2)*(-beta*reading_point(0) + alpha*reading_point(1) + reading_point(2) + t_z - reference_point(2));
112 T N_reading = normal(0)*(reading_direction(0) - gamma*reading_direction(1) + beta*reading_direction(2));
113 N_reading += normal(1)*(gamma*reading_direction(0) + reading_direction(1) - alpha*reading_direction(2));
114 N_reading += normal(2)*(-beta*reading_direction(0) + alpha*reading_direction(1) + reading_direction(2));
116 T N_reference = -(normal(0)*reference_direction(0) + normal(1)*reference_direction(1) + normal(2)*reference_direction(2));
119 tmp_vector_6 << normal(0), normal(1), normal(2), reading_range * n_alpha, reading_range * n_beta, reading_range * n_gamma;
121 J_hessian += tmp_vector_6 * tmp_vector_6.transpose();
123 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);
125 d2J_dReadingdX.block(0,valid_points_count,6,1) = tmp_vector_6;
127 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;
129 d2J_dReferencedX.block(0,valid_points_count,6,1) = tmp_vector_6;
131 valid_points_count++;
135 Matrix d2J_dZdX(Matrix::Zero(6, 2 * valid_points_count));
136 d2J_dZdX.block(0,0,6,valid_points_count) = d2J_dReadingdX.block(0,0,6,valid_points_count);
137 d2J_dZdX.block(0,valid_points_count,6,valid_points_count) = d2J_dReferencedX.block(0,0,6,valid_points_count);
139 Matrix inv_J_hessian = J_hessian.inverse();
141 covariance = d2J_dZdX * d2J_dZdX.transpose();
142 covariance = inv_J_hessian * covariance * inv_J_hessian;
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
TransformationParameters compute_in_place(ErrorElements &mPts)
PointMatcher< T >::Matrix Matrix
unsigned getNbPoints() const
Return the number of points contained in the point cloud.
Matrix estimateCovariance(const ErrorElements &mPts, const TransformationParameters &transformation)
PointToPointWithCovErrorMinimizer(const Parameters ¶ms=Parameters())
DataPoints reference
reference point cloud
virtual TransformationParameters compute(const ErrorElements &mPts)
Find the transformation that minimizes the error given matched pair of points. This function most be ...
PointMatcher< T >::Matrix Matrix
virtual Matrix getCovariance() const
If not redefined by child class, return zero matrix.
const M::mapped_type & get(const M &m, const typename M::key_type &k)
The superclass of classes that are constructed using generic parameters. This class provides the para...
PointMatcher< T >::Vector Vector
Matrix features
features of points in the cloud
PointMatcher< T >::TransformationParameters TransformationParameters
DataPoints reading
reading point cloud
Parametrizable::Parameters Parameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.