44 using namespace Eigen;
77 Matrix covariance(Matrix::Zero(6,6));
78 Matrix J_hessian(Matrix::Zero(6,6));
79 Matrix d2J_dReadingdX(Matrix::Zero(6, max_nbr_point));
80 Matrix d2J_dReferencedX(Matrix::Zero(6, max_nbr_point));
82 Vector reading_point(Vector::Zero(3));
83 Vector reference_point(Vector::Zero(3));
85 Vector reading_direction(Vector::Zero(3));
86 Vector reference_direction(Vector::Zero(3));
91 if (normals.rows() < 3)
92 return std::numeric_limits<T>::max() * Matrix::Identity(6,6);
101 Vector tmp_vector_6(Vector::Zero(6));
103 int valid_points_count = 0;
106 for(
int i = 0; i < max_nbr_point; ++i)
114 normal = normals.block(0,i,3,1);
116 T reading_range = reading_point.norm();
117 reading_direction = reading_point / reading_range;
118 T reference_range = reference_point.norm();
119 reference_direction = reference_point / reference_range;
121 T n_alpha = normal(2)*reading_direction(1) - normal(1)*reading_direction(2);
122 T n_beta = normal(0)*reading_direction(2) - normal(2)*reading_direction(0);
123 T n_gamma = normal(1)*reading_direction(0) - normal(0)*reading_direction(1);
125 T E = normal(0)*(reading_point(0) - gamma*reading_point(1) + beta*reading_point(2) + t_x - reference_point(0));
126 E += normal(1)*(gamma*reading_point(0) + reading_point(1) - alpha*reading_point(2) + t_y - reference_point(1));
127 E += normal(2)*(-beta*reading_point(0) + alpha*reading_point(1) + reading_point(2) + t_z - reference_point(2));
129 T N_reading = normal(0)*(reading_direction(0) - gamma*reading_direction(1) + beta*reading_direction(2));
130 N_reading += normal(1)*(gamma*reading_direction(0) + reading_direction(1) - alpha*reading_direction(2));
131 N_reading += normal(2)*(-beta*reading_direction(0) + alpha*reading_direction(1) + reading_direction(2));
133 T N_reference = -(normal(0)*reference_direction(0) + normal(1)*reference_direction(1) + normal(2)*reference_direction(2));
136 tmp_vector_6 << normal(0), normal(1), normal(2), reading_range * n_alpha, reading_range * n_beta, reading_range * n_gamma;
138 J_hessian += tmp_vector_6 * tmp_vector_6.transpose();
140 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);
142 d2J_dReadingdX.block(0,valid_points_count,6,1) = tmp_vector_6;
144 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;
146 d2J_dReferencedX.block(0,valid_points_count,6,1) = tmp_vector_6;
148 valid_points_count++;
152 Matrix d2J_dZdX(Matrix::Zero(6, 2 * valid_points_count));
153 d2J_dZdX.block(0,0,6,valid_points_count) = d2J_dReadingdX.block(0,0,6,valid_points_count);
154 d2J_dZdX.block(0,valid_points_count,6,valid_points_count) = d2J_dReferencedX.block(0,0,6,valid_points_count);
156 Matrix inv_J_hessian = J_hessian.inverse();
158 covariance = d2J_dZdX * d2J_dZdX.transpose();
159 covariance = inv_J_hessian * covariance * inv_J_hessian;
PointMatcher< T >::Matrix Matrix
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
virtual Matrix getCovariance() const
If not redefined by child class, return zero matrix.
virtual TransformationParameters compute(const ErrorElements &mPts)
Find the transformation that minimizes the error given matched pair of points. This function most be ...
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
unsigned getNbPoints() const
Return the number of points contained in the point cloud.
PointMatcherSupport::Parametrizable Parametrizable
DataPoints reference
reference point cloud
TransformationParameters compute_in_place(ErrorElements &mPts)
Matrix estimateCovariance(const ErrorElements &mPts, const TransformationParameters &transformation)
PointMatcher< T >::Vector Vector
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
PointToPlaneWithCovErrorMinimizer(const Parameters ¶ms=Parameters())
Parametrizable::ParametersDoc ParametersDoc
PointMatcherSupport::Parametrizable P
Parametrizable::Parameters Parameters
const M::mapped_type & get(const M &m, const typename M::key_type &k)
The documentation of a parameter.
Parametrizable::ParameterDoc ParameterDoc
The superclass of classes that are constructed using generic parameters. This class provides the para...
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
PointMatcher< T >::TransformationParameters TransformationParameters
Matrix features
features of points in the cloud
Parametrizable::Parameters Parameters
DataPoints reading
reading point cloud
Matrix TransformationParameters
A matrix holding the parameters a transformation.