41#ifndef PCL_REGISTRATION_NDT_IMPL_H_
42#define PCL_REGISTRATION_NDT_IMPL_H_
46template <
typename Po
intSource,
typename Po
intTarget>
56 reg_name_ =
"NormalDistributionsTransform";
61 const double gauss_d3 = -std::log(gauss_c2);
62 gauss_d1_ = -std::log(gauss_c1 + gauss_c2) - gauss_d3;
64 -2 * std::log((-std::log(gauss_c1 * std::exp(-0.5) + gauss_c2) - gauss_d3) /
71template <
typename Po
intSource,
typename Po
intTarget>
82 const double gauss_d3 = -std::log(gauss_c2);
83 gauss_d1_ = -std::log(gauss_c1 + gauss_c2) - gauss_d3;
85 -2 * std::log((-std::log(gauss_c1 * std::exp(-0.5) + gauss_c2) - gauss_d3) /
88 if (guess != Eigen::Matrix4f::Identity()) {
100 Eigen::Transform<float, 3, Eigen::Affine, Eigen::ColMajor> eig_transformation;
104 Eigen::Matrix<double, 6, 1> transform, score_gradient;
105 Eigen::Vector3f init_translation = eig_transformation.translation();
106 Eigen::Vector3f init_rotation = eig_transformation.rotation().eulerAngles(0, 1, 2);
107 transform << init_translation.cast<
double>(), init_rotation.cast<
double>();
109 Eigen::Matrix<double, 6, 6> hessian;
121 Eigen::JacobiSVD<Eigen::Matrix<double, 6, 6>> sv(
122 hessian, Eigen::ComputeFullU | Eigen::ComputeFullV);
124 Eigen::Matrix<double, 6, 1> delta = sv.solve(-score_gradient);
127 double delta_norm = delta.norm();
129 if (delta_norm == 0 || std::isnan(delta_norm)) {
156 const double cos_angle =
158 const double translation_sqr =
182template <
typename Po
intSource,
typename Po
intTarget>
185 Eigen::Matrix<double, 6, 1>& score_gradient,
186 Eigen::Matrix<double, 6, 6>& hessian,
188 const Eigen::Matrix<double, 6, 1>& transform,
189 bool compute_hessian)
191 score_gradient.setZero();
199 for (std::size_t idx = 0; idx <
input_->size(); idx++) {
201 const auto& x_trans_pt = trans_cloud[idx];
205 std::vector<TargetGridLeafConstPtr> neighborhood;
209 for (
const auto& cell : neighborhood) {
211 const auto& x_pt = (*input_)[idx];
212 const Eigen::Vector3d x = x_pt.getVector3fMap().template cast<double>();
215 const Eigen::Vector3d x_trans =
216 x_trans_pt.getVector3fMap().template cast<double>() - cell->getMean();
219 const Eigen::Matrix3d c_inv = cell->getInverseCov();
233template <
typename Po
intSource,
typename Po
intTarget>
236 const Eigen::Matrix<double, 6, 1>& transform,
bool compute_hessian)
239 const auto calculate_cos_sin = [](
double angle,
double& c,
double& s) {
240 if (std::abs(angle) < 10e-5) {
250 double cx, cy, cz, sx, sy, sz;
251 calculate_cos_sin(transform(3), cx, sx);
252 calculate_cos_sin(transform(4), cy, sy);
253 calculate_cos_sin(transform(5), cz, sz);
259 (-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy), 1.0);
261 (cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy), 1.0);
263 Eigen::Vector4d((-sy * cz), sy * sz, cy, 1.0);
265 Eigen::Vector4d(sx * cy * cz, (-sx * cy * sz), sx * sy, 1.0);
267 Eigen::Vector4d((-cx * cy * cz), cx * cy * sz, (-cx * sy), 1.0);
269 Eigen::Vector4d((-cy * sz), (-cy * cz), 0, 1.0);
271 Eigen::Vector4d((cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0, 1.0);
273 Eigen::Vector4d((sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0, 1.0);
275 if (compute_hessian) {
280 (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy, 0.0f);
282 (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), (-cx * cy), 0.0f);
285 Eigen::Vector4d((cx * cy * cz), (-cx * cy * sz), (cx * sy), 0.0f);
287 Eigen::Vector4d((sx * cy * cz), (-sx * cy * sz), (sx * sy), 0.0f);
291 (-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0, 0.0f);
293 (cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0, 0.0f);
296 Eigen::Vector4d((-cy * cz), (cy * sz), (-sy), 0.0f);
298 Eigen::Vector4d((-sx * sy * cz), (sx * sy * sz), (sx * cy), 0.0f);
300 Eigen::Vector4d((cx * sy * cz), (-cx * sy * sz), (-cx * cy), 0.0f);
303 Eigen::Vector4d((sy * sz), (sy * cz), 0, 0.0f);
305 Eigen::Vector4d((-sx * cy * sz), (-sx * cy * cz), 0, 0.0f);
307 Eigen::Vector4d((cx * cy * sz), (cx * cy * cz), 0, 0.0f);
310 Eigen::Vector4d((-cy * cz), (cy * sz), 0, 0.0f);
312 (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0, 0.0f);
314 (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0, 0.0f);
318template <
typename Po
intSource,
typename Po
intTarget>
321 const Eigen::Vector3d& x,
bool compute_hessian)
326 Eigen::Matrix<double, 8, 1> point_angular_jacobian =
337 if (compute_hessian) {
338 Eigen::Matrix<double, 15, 1> point_angular_hessian =
342 const Eigen::Vector3d a(0, point_angular_hessian[0], point_angular_hessian[1]);
343 const Eigen::Vector3d b(0, point_angular_hessian[2], point_angular_hessian[3]);
344 const Eigen::Vector3d c(0, point_angular_hessian[4], point_angular_hessian[5]);
345 const Eigen::Vector3d d = point_angular_hessian.block<3, 1>(6, 0);
346 const Eigen::Vector3d e = point_angular_hessian.block<3, 1>(9, 0);
347 const Eigen::Vector3d f = point_angular_hessian.block<3, 1>(12, 0);
364template <
typename Po
intSource,
typename Po
intTarget>
367 Eigen::Matrix<double, 6, 1>& score_gradient,
368 Eigen::Matrix<double, 6, 6>& hessian,
369 const Eigen::Vector3d& x_trans,
370 const Eigen::Matrix3d& c_inv,
371 bool compute_hessian)
const
374 double e_x_cov_x = std::exp(-
gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2);
377 const double score_inc = -
gauss_d1_ * e_x_cov_x;
382 if (e_x_cov_x > 1 || e_x_cov_x < 0 || std::isnan(e_x_cov_x)) {
389 for (
int i = 0; i < 6; i++) {
395 score_gradient(i) += x_trans.dot(cov_dxd_pi) * e_x_cov_x;
397 if (compute_hessian) {
398 for (Eigen::Index j = 0; j < hessian.cols(); j++) {
401 e_x_cov_x * (-
gauss_d2_ * x_trans.dot(cov_dxd_pi) *
412template <
typename Po
intSource,
typename Po
intTarget>
422 for (std::size_t idx = 0; idx <
input_->size(); idx++) {
424 const auto& x_trans_pt = trans_cloud[idx];
428 std::vector<TargetGridLeafConstPtr> neighborhood;
432 for (
const auto& cell : neighborhood) {
434 const auto& x_pt = (*input_)[idx];
435 const Eigen::Vector3d x = x_pt.getVector3fMap().template cast<double>();
438 const Eigen::Vector3d x_trans =
439 x_trans_pt.getVector3fMap().template cast<double>() - cell->getMean();
442 const Eigen::Matrix3d c_inv = cell->getInverseCov();
454template <
typename Po
intSource,
typename Po
intTarget>
457 Eigen::Matrix<double, 6, 6>& hessian,
458 const Eigen::Vector3d& x_trans,
459 const Eigen::Matrix3d& c_inv)
const
466 if (e_x_cov_x > 1 || e_x_cov_x < 0 || std::isnan(e_x_cov_x)) {
473 for (
int i = 0; i < 6; i++) {
478 for (Eigen::Index j = 0; j < hessian.cols(); j++) {
481 e_x_cov_x * (-
gauss_d2_ * x_trans.dot(cov_dxd_pi) *
489template <
typename Po
intSource,
typename Po
intTarget>
512 if (g_t * (a_l - a_t) > 0) {
520 if (g_t * (a_l - a_t) < 0) {
534template <
typename Po
intSource,
typename Po
intTarget>
547 if (a_t == a_l && a_t == a_u) {
552 enum class EndpointsCondition { Case1, Case2, Case3, Case4 };
553 EndpointsCondition condition;
556 condition = EndpointsCondition::Case4;
558 else if (f_t > f_l) {
559 condition = EndpointsCondition::Case1;
561 else if (g_t * g_l < 0) {
562 condition = EndpointsCondition::Case2;
564 else if (std::fabs(g_t) <= std::fabs(g_l)) {
565 condition = EndpointsCondition::Case3;
568 condition = EndpointsCondition::Case4;
572 case EndpointsCondition::Case1: {
575 const double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
576 const double w = std::sqrt(z * z - g_t * g_l);
578 const double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
583 a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t));
585 if (std::fabs(a_c - a_l) < std::fabs(a_q - a_l)) {
588 return 0.5 * (a_q + a_c);
591 case EndpointsCondition::Case2: {
594 const double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
595 const double w = std::sqrt(z * z - g_t * g_l);
597 const double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
601 const double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
603 if (std::fabs(a_c - a_t) >= std::fabs(a_s - a_t)) {
609 case EndpointsCondition::Case3: {
612 const double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
613 const double w = std::sqrt(z * z - g_t * g_l);
614 const double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
618 const double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
622 if (std::fabs(a_c - a_t) < std::fabs(a_s - a_t)) {
630 return std::min(a_t + 0.66 * (a_u - a_t), a_t_next);
632 return std::max(a_t + 0.66 * (a_u - a_t), a_t_next);
636 case EndpointsCondition::Case4: {
639 const double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u;
640 const double w = std::sqrt(z * z - g_t * g_u);
642 return a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w);
647template <
typename Po
intSource,
typename Po
intTarget>
650 const Eigen::Matrix<double, 6, 1>& x,
651 Eigen::Matrix<double, 6, 1>& step_dir,
656 Eigen::Matrix<double, 6, 1>& score_gradient,
657 Eigen::Matrix<double, 6, 6>& hessian,
661 const double phi_0 = -score;
663 double d_phi_0 = -(score_gradient.dot(step_dir));
677 const int max_step_iterations = 10;
678 int step_iterations = 0;
681 const double mu = 1.e-4;
683 const double nu = 0.9;
686 double a_l = 0, a_u = 0;
698 bool interval_converged = (step_max - step_min) < 0, open_interval =
true;
700 double a_t = step_init;
701 a_t = std::min(a_t, step_max);
702 a_t = std::max(a_t, step_min);
704 Eigen::Matrix<double, 6, 1> x_t = x + step_dir * a_t;
719 double phi_t = -score;
721 double d_phi_t = -(score_gradient.dot(step_dir));
731 while (!interval_converged && step_iterations < max_step_iterations &&
733 d_phi_t <= -nu * d_phi_0 )) {
742 a_t = std::min(a_t, step_max);
743 a_t = std::max(a_t, step_min);
745 x_t = x + step_dir * a_t;
760 d_phi_t = -(score_gradient.dot(step_dir));
768 if (open_interval && (psi_t <= 0 && d_psi_t >= 0)) {
769 open_interval =
false;
772 f_l += phi_0 - mu * d_phi_0 * a_l;
776 f_u += phi_0 - mu * d_phi_0 * a_u;
798 if (step_iterations) {
PointCloudConstPtr input_
Matrix4 final_transformation_
The final transformation matrix estimated by the registration method after N iterations.
std::function< UpdateVisualizerCallbackSignature > update_visualizer_
Callback function to update intermediate source point cloud position during it's registration to the ...
std::string reg_name_
The registration method name.
Matrix4 transformation_
The transformation matrix estimated by the registration method.
int nr_iterations_
The number of iterations the internal optimization ran for (used internally).
Matrix4 previous_transformation_
The previous transformation matrix estimated by the registration method (used internally).
bool converged_
Holds internal convergence state, given user parameters.
int max_iterations_
The maximum number of iterations the internal optimization should run for.
double transformation_rotation_epsilon_
The maximum rotation difference between two consecutive transformations in order to consider converge...
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
PointCloudTargetConstPtr target_
The input point cloud dataset target.
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields)
Apply a rigid transform defined by a 4x4 matrix.
IndicesAllocator<> Indices
Type used for indices in PCL.