56 #ifndef NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
57 #define NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
65 #include <experimental/optional>
67 #include <Eigen/Geometry>
76 namespace localization
81 template<
typename ScalarT>
85 if (std::isnan(p) || p > ScalarT{1.0} || p < ScalarT{0.0}) {
94 template<
typename MapT>
96 EigenPose<Real>, 1U, 6U, common::optimization::EigenComparator>
126 : m_scan_ref(scan), m_map_ref(map)
134 Eigen::Transform<float64_t, 3, Eigen::Affine, Eigen::ColMajor> transform;
135 transform.setIdentity();
141 std::experimental::optional<GradientAngleParameters> grad_params;
144 std::experimental::optional<HessianAngleParameters> hessian_params;
148 const AngleParameters angle_params{
x};
152 grad_params.emplace(angle_params);
156 hessian_params.emplace(angle_params);
160 for (
const auto & pt : m_scan_ref) {
165 point_gradient.setZero();
166 point_gradient.block<3, 3>(0, 0).setIdentity();
167 compute_point_gradients(grad_params.value(), pt, point_gradient);
170 point_hessian.setZero();
171 compute_point_hessians(hessian_params.value(), pt, point_hessian);
175 const Point pt_trans = transform * pt;
176 const auto & cells = m_map_ref.cell(pt_trans);
178 for (
const auto & cell : cells) {
179 const Point pt_trans_norm = pt_trans - cell.centroid();
182 const auto & inv_cov = cell.inverse_covariance();
184 Real e_x_cov_x = std::exp(
185 -m_gauss_d2 * pt_trans_norm.dot(
186 inv_cov * pt_trans_norm) / 2.0);
189 score += -m_gauss_d1 * e_x_cov_x;
193 const auto d2_e_x_cov_x = m_gauss_d2 * e_x_cov_x;
203 const auto d1_d2_e_x_cov_x = m_gauss_d1 * d2_e_x_cov_x;
205 for (
auto i = 0U; i <
jacobian.rows(); ++i) {
206 const Point cov_dxd_pi = inv_cov * point_gradient.col(i);
208 jacobian(i) += pt_trans_norm.dot(cov_dxd_pi) * d1_d2_e_x_cov_x;
211 for (
auto j = 0U; j <
hessian.cols(); ++j) {
212 hessian(i, j) += d1_d2_e_x_cov_x * (-m_gauss_d2 * pt_trans_norm.dot(cov_dxd_pi) *
213 pt_trans_norm.dot(inv_cov * point_gradient.col(j)) +
214 pt_trans_norm.dot(inv_cov * point_hessian.block<3, 1>(3 * i, j)) +
215 point_gradient.col(j).dot(cov_dxd_pi));
236 struct AngleParameters
239 static constexpr
auto approx_thresh{10e-5};
240 AngleParameters() =
delete;
243 if (std::fabs(pose(3)) < approx_thresh) {
247 cx = std::cos(pose(3));
248 sx = std::sin(pose(3));
251 if (std::fabs(pose(4)) < approx_thresh) {
255 cy = std::cos(pose(4));
256 sy = std::sin(pose(4));
259 if (std::fabs(pose(5)) < approx_thresh) {
263 cz = std::cos(pose(5));
264 sz = std::sin(pose(5));
277 struct GradientAngleParameters
280 GradientAngleParameters() =
delete;
281 explicit GradientAngleParameters(
const AngleParameters & params)
283 j_ang_a(0) = -params.sx * params.sz + params.cx * params.sy * params.cz;
284 j_ang_a(1) = -params.sx * params.cz - params.cx * params.sy * params.sz;
285 j_ang_a(2) = -params.cx * params.cy;
287 j_ang_b(0) = params.cx * params.sz + params.sx * params.sy * params.cz;
288 j_ang_b(1) = params.cx * params.cz - params.sx * params.sy * params.sz;
289 j_ang_b(2) = -params.sx * params.cy;
291 j_ang_c(0) = -params.sy * params.cz;
292 j_ang_c(1) = params.sy * params.sz;
293 j_ang_c(2) = params.cy;
295 j_ang_d(0) = params.sx * params.cy * params.cz;
296 j_ang_d(1) = -params.sx * params.cy * params.sz;
297 j_ang_d(2) = params.sx * params.sy;
299 j_ang_e(0) = -params.cx * params.cy * params.cz;
300 j_ang_e(1) = params.cx * params.cy * params.sz;
301 j_ang_e(2) = -params.cx * params.sy;
303 j_ang_f(0) = -params.cy * params.sz;
304 j_ang_f(1) = -params.cy * params.cz;
307 j_ang_g(0) = params.cx * params.cz - params.sx * params.sy * params.sz;
308 j_ang_g(1) = -params.cx * params.sz - params.sx * params.sy * params.cz;
311 j_ang_h(0) = params.sx * params.cz + params.cx * params.sy * params.sz;
312 j_ang_h(1) = params.cx * params.sy * params.cz - params.sx * params.sz;
316 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;
320 struct HessianAngleParameters
323 HessianAngleParameters() =
delete;
324 explicit HessianAngleParameters(
const AngleParameters & params)
326 h_ang_a2(0) = -params.cx * params.sz - params.sx * params.sy * params.cz;
327 h_ang_a2(1) = -params.cx * params.cz + params.sx * params.sy * params.sz;
328 h_ang_a2(2) = params.sx * params.cy;
330 h_ang_a3(0) = -params.sx * params.sz + params.cx * params.sy * params.cz;
331 h_ang_a3(1) = -params.cx * params.sy * params.sz - params.sx * params.cz;
332 h_ang_a3(2) = -params.cx * params.cy;
334 h_ang_b2(0) = params.cx * params.cy * params.cz;
335 h_ang_b2(1) = -params.cx * params.cy * params.sz;
336 h_ang_b2(2) = params.cx * params.sy;
338 h_ang_b3(0) = params.sx * params.cy * params.cz;
339 h_ang_b3(1) = -params.sx * params.cy * params.sz;
340 h_ang_b3(2) = params.sx * params.sy;
342 h_ang_c2(0) = -params.sx * params.cz - params.cx * params.sy * params.sz;
343 h_ang_c2(1) = params.sx * params.sz - params.cx * params.sy * params.cz;
346 h_ang_c3(0) = params.cx * params.cz - params.sx * params.sy * params.sz;
347 h_ang_c3(1) = -params.sx * params.sy * params.cz - params.cx * params.sz;
350 h_ang_d1(0) = -params.cy * params.cz;
351 h_ang_d1(1) = params.cy * params.sz;
352 h_ang_d1(2) = params.sy;
354 h_ang_d2(0) = -params.sx * params.sy * params.cz;
355 h_ang_d2(1) = params.sx * params.sy * params.sz;
356 h_ang_d2(2) = params.sx * params.cy;
358 h_ang_d3(0) = params.cx * params.sy * params.cz;
359 h_ang_d3(1) = -params.cx * params.sy * params.sz;
360 h_ang_d3(2) = -params.cx * params.cy;
362 h_ang_e1(0) = params.sy * params.sz;
363 h_ang_e1(1) = params.sy * params.cz;
366 h_ang_e2(0) = -params.sx * params.cy * params.sz;
367 h_ang_e2(1) = -params.sx * params.cy * params.cz;
370 h_ang_e3(0) = params.cx * params.cy * params.sz;
371 h_ang_e3(1) = params.cx * params.cy * params.cz;
374 h_ang_f1(0) = -params.cy * params.cz;
375 h_ang_f1(1) = params.cy * params.sz;
378 h_ang_f2(0) = -params.cx * params.sz - params.sx * params.sy * params.cz;
379 h_ang_f2(1) = -params.cx * params.cz + params.sx * params.sy * params.sz;
382 h_ang_f3(0) = -params.sx * params.sz + params.cx * params.sy * params.cz;
383 h_ang_f3(1) = -params.cx * params.sy * params.sz - params.sx * params.cz;
387 Point h_ang_a2, h_ang_a3,
390 h_ang_d1, h_ang_d2, h_ang_d3,
391 h_ang_e1, h_ang_e2, h_ang_e3,
392 h_ang_f1, h_ang_f2, h_ang_f3;
395 void compute_point_gradients(
396 const GradientAngleParameters & params,
400 point_gradient(1, 3) =
x.dot(params.j_ang_a);
401 point_gradient(2, 3) =
x.dot(params.j_ang_b);
402 point_gradient(0, 4) =
x.dot(params.j_ang_c);
403 point_gradient(1, 4) =
x.dot(params.j_ang_d);
404 point_gradient(2, 4) =
x.dot(params.j_ang_e);
405 point_gradient(0, 5) =
x.dot(params.j_ang_f);
406 point_gradient(1, 5) =
x.dot(params.j_ang_g);
407 point_gradient(2, 5) =
x.dot(params.j_ang_h);
410 void compute_point_hessians(
411 const HessianAngleParameters & params,
415 const Point a{0.0,
x.dot(params.h_ang_a2),
x.dot(params.h_ang_a3)};
416 const Point b{0.0,
x.dot(params.h_ang_b2),
x.dot(params.h_ang_b3)};
417 const Point c{0.0,
x.dot(params.h_ang_c2),
x.dot(params.h_ang_c3)};
418 const Point d{
x.dot(params.h_ang_d1),
x.dot(params.h_ang_d2),
419 x.dot(params.h_ang_d3)};
420 const Point e{
x.dot(params.h_ang_e1),
x.dot(params.h_ang_e2),
421 x.dot(params.h_ang_e3)};
422 const Point f{
x.dot(params.h_ang_f1),
x.dot(params.h_ang_f2),
423 x.dot(params.h_ang_f3)};
425 point_hessian.block<3, 1>(9, 3) =
a;
426 point_hessian.block<3, 1>(12, 3) = b;
427 point_hessian.block<3, 1>(15, 3) = c;
428 point_hessian.block<3, 1>(9, 4) = b;
429 point_hessian.block<3, 1>(12, 4) = d;
430 point_hessian.block<3, 1>(15, 4) = e;
431 point_hessian.block<3, 1>(9, 5) = c;
432 point_hessian.block<3, 1>(12, 5) = e;
433 point_hessian.block<3, 1>(15, 5) =
f;
439 void init(
Real outlier_ratio)
442 throw std::domain_error(
"Outlier ratio must be between 0 and 1");
444 const auto c_size = m_map_ref.cell_size();
448 const auto gauss_c1 = 10.0 * (1.0 - outlier_ratio);
449 const auto gauss_c2 = outlier_ratio /
static_cast<Real>(c_size.x * c_size.y * c_size.z);
450 const auto gauss_d3 = -std::log(gauss_c2);
451 m_gauss_d1 = -std::log(gauss_c1 + gauss_c2) - gauss_d3;
453 std::log((-std::log(gauss_c1 * std::exp(-0.5) + gauss_c2) - gauss_d3) / m_gauss_d1);
457 const Scan & m_scan_ref;
458 const Map & m_map_ref;
460 Real m_gauss_d1{0.0};
461 Real m_gauss_d2{0.0};
464 template<
typename MapT>
466 common::optimization::UnconstrainedOptimizationProblem<P2DNDTObjective<MapT>, EigenPose<Real>,
472 #endif // NDT__NDT_OPTIMIZATION_PROBLEM_HPP_