56 #ifndef NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
57 #define NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
67 #include <experimental/optional>
69 #include <Eigen/Geometry>
79 namespace localization
84 template<
typename ScalarT>
89 constexpr
auto eps = std::numeric_limits<ScalarT>::epsilon();
90 return std::isfinite(p) &&
abs_lte(p, 1.0, eps) &&
abs_gte(p, 0.0, eps);
97 template<
typename MapT,
100 EigenPose<Real>, 1U, 6U, common::optimization::EigenComparator>
130 : m_scan_ref(scan), m_map_ref(map)
138 Eigen::Transform<float64_t, 3, Eigen::Affine, Eigen::ColMajor> transform;
139 transform.setIdentity();
145 std::experimental::optional<GradientAngleParameters> grad_params;
148 std::experimental::optional<HessianAngleParameters> hessian_params;
152 const AngleParameters angle_params{
x};
156 grad_params.emplace(angle_params);
160 hessian_params.emplace(angle_params);
164 for (
const auto & pt : m_scan_ref) {
169 point_gradient.setZero();
170 point_gradient.block<3, 3>(0, 0).setIdentity();
171 compute_point_gradients(grad_params.value(), pt, point_gradient);
174 point_hessian.setZero();
175 compute_point_hessians(hessian_params.value(), pt, point_hessian);
179 const Point pt_trans = transform * pt;
180 const auto & cells = m_map_ref.cell(pt_trans);
182 for (
const auto & cell : cells) {
183 const Point pt_trans_norm = pt_trans - cell.centroid();
185 if (!cell.usable()) {
188 const auto & inv_cov = cell.inverse_covariance();
190 Real e_minus_half_d2_x_cov_x =
191 std::exp(-m_gauss_d2 * pt_trans_norm.dot(inv_cov * pt_trans_norm) / 2.0);
194 score += -m_gauss_d1 * e_minus_half_d2_x_cov_x;
200 const auto d2_e_minus_half_d2_x_cov_x = m_gauss_d2 * e_minus_half_d2_x_cov_x;
208 const auto d1_d2_e_minus_half_d2_x_cov_x = m_gauss_d1 * d2_e_minus_half_d2_x_cov_x;
210 for (
auto i = 0U; i <
jacobian.rows(); ++i) {
211 const Point cov_dxd_pi = inv_cov * point_gradient.col(i);
213 jacobian(i) += pt_trans_norm.dot(cov_dxd_pi) * d1_d2_e_minus_half_d2_x_cov_x;
216 for (
auto j = 0U; j <
hessian.cols(); ++j) {
217 hessian(i, j) += d1_d2_e_minus_half_d2_x_cov_x *
218 (-m_gauss_d2 * pt_trans_norm.dot(cov_dxd_pi) *
219 pt_trans_norm.dot(inv_cov * point_gradient.col(j)) +
220 pt_trans_norm.dot(inv_cov * point_hessian.block<3, 1>(3 * i, j)) +
221 point_gradient.col(j).dot(cov_dxd_pi));
240 struct AngleParameters
243 static constexpr
auto approx_thresh{10e-5};
244 AngleParameters() =
delete;
247 if (std::fabs(pose(3)) < approx_thresh) {
251 cx = std::cos(pose(3));
252 sx = std::sin(pose(3));
255 if (std::fabs(pose(4)) < approx_thresh) {
259 cy = std::cos(pose(4));
260 sy = std::sin(pose(4));
263 if (std::fabs(pose(5)) < approx_thresh) {
267 cz = std::cos(pose(5));
268 sz = std::sin(pose(5));
281 struct GradientAngleParameters
284 GradientAngleParameters() =
delete;
285 explicit GradientAngleParameters(
const AngleParameters & params)
287 j_ang_a(0) = -params.sx * params.sz + params.cx * params.sy * params.cz;
288 j_ang_a(1) = -params.sx * params.cz - params.cx * params.sy * params.sz;
289 j_ang_a(2) = -params.cx * params.cy;
291 j_ang_b(0) = params.cx * params.sz + params.sx * params.sy * params.cz;
292 j_ang_b(1) = params.cx * params.cz - params.sx * params.sy * params.sz;
293 j_ang_b(2) = -params.sx * params.cy;
295 j_ang_c(0) = -params.sy * params.cz;
296 j_ang_c(1) = params.sy * params.sz;
297 j_ang_c(2) = params.cy;
299 j_ang_d(0) = params.sx * params.cy * params.cz;
300 j_ang_d(1) = -params.sx * params.cy * params.sz;
301 j_ang_d(2) = params.sx * params.sy;
303 j_ang_e(0) = -params.cx * params.cy * params.cz;
304 j_ang_e(1) = params.cx * params.cy * params.sz;
305 j_ang_e(2) = -params.cx * params.sy;
307 j_ang_f(0) = -params.cy * params.sz;
308 j_ang_f(1) = -params.cy * params.cz;
311 j_ang_g(0) = params.cx * params.cz - params.sx * params.sy * params.sz;
312 j_ang_g(1) = -params.cx * params.sz - params.sx * params.sy * params.cz;
315 j_ang_h(0) = params.sx * params.cz + params.cx * params.sy * params.sz;
316 j_ang_h(1) = params.cx * params.sy * params.cz - params.sx * params.sz;
320 Point j_ang_a, j_ang_b, j_ang_c, j_ang_d, j_ang_e, j_ang_f, j_ang_g, j_ang_h;
324 struct HessianAngleParameters
327 HessianAngleParameters() =
delete;
328 explicit HessianAngleParameters(
const AngleParameters & params)
330 h_ang_a2(0) = -params.cx * params.sz - params.sx * params.sy * params.cz;
331 h_ang_a2(1) = -params.cx * params.cz + params.sx * params.sy * params.sz;
332 h_ang_a2(2) = params.sx * params.cy;
334 h_ang_a3(0) = -params.sx * params.sz + params.cx * params.sy * params.cz;
335 h_ang_a3(1) = -params.cx * params.sy * params.sz - params.sx * params.cz;
336 h_ang_a3(2) = -params.cx * params.cy;
338 h_ang_b2(0) = params.cx * params.cy * params.cz;
339 h_ang_b2(1) = -params.cx * params.cy * params.sz;
340 h_ang_b2(2) = params.cx * params.sy;
342 h_ang_b3(0) = params.sx * params.cy * params.cz;
343 h_ang_b3(1) = -params.sx * params.cy * params.sz;
344 h_ang_b3(2) = params.sx * params.sy;
346 h_ang_c2(0) = -params.sx * params.cz - params.cx * params.sy * params.sz;
347 h_ang_c2(1) = params.sx * params.sz - params.cx * params.sy * params.cz;
350 h_ang_c3(0) = params.cx * params.cz - params.sx * params.sy * params.sz;
351 h_ang_c3(1) = -params.sx * params.sy * params.cz - params.cx * params.sz;
354 h_ang_d1(0) = -params.cy * params.cz;
355 h_ang_d1(1) = params.cy * params.sz;
356 h_ang_d1(2) = params.sy;
358 h_ang_d2(0) = -params.sx * params.sy * params.cz;
359 h_ang_d2(1) = params.sx * params.sy * params.sz;
360 h_ang_d2(2) = params.sx * params.cy;
362 h_ang_d3(0) = params.cx * params.sy * params.cz;
363 h_ang_d3(1) = -params.cx * params.sy * params.sz;
364 h_ang_d3(2) = -params.cx * params.cy;
366 h_ang_e1(0) = params.sy * params.sz;
367 h_ang_e1(1) = params.sy * params.cz;
370 h_ang_e2(0) = -params.sx * params.cy * params.sz;
371 h_ang_e2(1) = -params.sx * params.cy * params.cz;
374 h_ang_e3(0) = params.cx * params.cy * params.sz;
375 h_ang_e3(1) = params.cx * params.cy * params.cz;
378 h_ang_f1(0) = -params.cy * params.cz;
379 h_ang_f1(1) = params.cy * params.sz;
382 h_ang_f2(0) = -params.cx * params.sz - params.sx * params.sy * params.cz;
383 h_ang_f2(1) = -params.cx * params.cz + params.sx * params.sy * params.sz;
386 h_ang_f3(0) = -params.sx * params.sz + params.cx * params.sy * params.cz;
387 h_ang_f3(1) = -params.cx * params.sy * params.sz - params.sx * params.cz;
391 Point h_ang_a2, h_ang_a3,
394 h_ang_d1, h_ang_d2, h_ang_d3,
395 h_ang_e1, h_ang_e2, h_ang_e3,
396 h_ang_f1, h_ang_f2, h_ang_f3;
399 void compute_point_gradients(
400 const GradientAngleParameters & params,
404 point_gradient(1, 3) =
x.dot(params.j_ang_a);
405 point_gradient(2, 3) =
x.dot(params.j_ang_b);
406 point_gradient(0, 4) =
x.dot(params.j_ang_c);
407 point_gradient(1, 4) =
x.dot(params.j_ang_d);
408 point_gradient(2, 4) =
x.dot(params.j_ang_e);
409 point_gradient(0, 5) =
x.dot(params.j_ang_f);
410 point_gradient(1, 5) =
x.dot(params.j_ang_g);
411 point_gradient(2, 5) =
x.dot(params.j_ang_h);
414 void compute_point_hessians(
415 const HessianAngleParameters & params,
419 const Point a{0.0,
x.dot(params.h_ang_a2),
x.dot(params.h_ang_a3)};
420 const Point b{0.0,
x.dot(params.h_ang_b2),
x.dot(params.h_ang_b3)};
421 const Point c{0.0,
x.dot(params.h_ang_c2),
x.dot(params.h_ang_c3)};
422 const Point d{
x.dot(params.h_ang_d1),
x.dot(params.h_ang_d2),
423 x.dot(params.h_ang_d3)};
424 const Point e{
x.dot(params.h_ang_e1),
x.dot(params.h_ang_e2),
425 x.dot(params.h_ang_e3)};
426 const Point f{
x.dot(params.h_ang_f1),
x.dot(params.h_ang_f2),
427 x.dot(params.h_ang_f3)};
429 point_hessian.block<3, 1>(9, 3) = a;
430 point_hessian.block<3, 1>(12, 3) = b;
431 point_hessian.block<3, 1>(15, 3) = c;
432 point_hessian.block<3, 1>(9, 4) = b;
433 point_hessian.block<3, 1>(12, 4) = d;
434 point_hessian.block<3, 1>(15, 4) = e;
435 point_hessian.block<3, 1>(9, 5) = c;
436 point_hessian.block<3, 1>(12, 5) = e;
437 point_hessian.block<3, 1>(15, 5) =
f;
443 void init(
Real outlier_ratio)
446 throw std::domain_error(
"Outlier ratio must be between 0 and 1");
448 const auto c_size = m_map_ref.cell_size();
452 const auto gauss_c1 = 10.0 * (1.0 - outlier_ratio);
453 const auto gauss_c2 = outlier_ratio /
static_cast<Real>(c_size.x * c_size.y * c_size.z);
454 const auto gauss_d3 = -std::log(gauss_c2);
455 m_gauss_d1 = -std::log(gauss_c1 + gauss_c2) - gauss_d3;
457 std::log((-std::log(gauss_c1 * std::exp(-0.5) + gauss_c2) - gauss_d3) / m_gauss_d1);
461 const Scan & m_scan_ref;
462 const Map & m_map_ref;
464 Real m_gauss_d1{0.0};
465 Real m_gauss_d2{0.0};
468 template<
typename MapT>
470 common::optimization::UnconstrainedOptimizationProblem<P2DNDTObjective<MapT>, EigenPose<Real>,
476 #endif // NDT__NDT_OPTIMIZATION_PROBLEM_HPP_