Autoware.Auto
ndt_optimization_problem.hpp
Go to the documentation of this file.
1 // Copyright 2019 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 
18 // This file contains modified code from the following open source projects
19 // published under the licenses listed below:
20 //
21 // Software License Agreement (BSD License)
22 //
23 // Point Cloud Library (PCL) - www.pointclouds.org
24 // Copyright (c) 2010-2011, Willow Garage, Inc.
25 // Copyright (c) 2012-, Open Perception, Inc.
26 //
27 // All rights reserved.
28 //
29 // Redistribution and use in source and binary forms, with or without
30 // modification, are permitted provided that the following conditions
31 // are met:
32 //
33 // * Redistributions of source code must retain the above copyright
34 // notice, this list of conditions and the following disclaimer.
35 // * Redistributions in binary form must reproduce the above
36 // copyright notice, this list of conditions and the following
37 // disclaimer in the documentation and/or other materials provided
38 // with the distribution.
39 // * Neither the name of the copyright holder(s) nor the names of its
40 // contributors may be used to endorse or promote products derived
41 // from this software without specific prior written permission.
42 //
43 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
44 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
45 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
46 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
47 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
48 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
49 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
50 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
51 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
52 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
53 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
54 // POSSIBILITY OF SUCH DAMAGE.
55 
56 #ifndef NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
57 #define NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
58 
60 #include <ndt/ndt_map.hpp>
61 #include <ndt/ndt_scan.hpp>
62 #include <ndt/ndt_config.hpp>
64 #include <optimization/utils.hpp>
65 #include <ndt/utils.hpp>
66 #include <ndt/constraints.hpp>
67 #include <experimental/optional>
68 #include <Eigen/Core>
69 #include <Eigen/Geometry>
70 #include <limits>
71 #include <tuple>
72 #include "common/types.hpp"
73 
76 
77 namespace autoware
78 {
79 namespace localization
80 {
81 namespace ndt
82 {
83 
84 template<typename ScalarT>
86 {
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);
91 }
92 
97 template<typename MapT,
99 class P2DNDTObjective : public common::optimization::CachedExpression<P2DNDTObjective<MapT>,
100  EigenPose<Real>, 1U, 6U, common::optimization::EigenComparator>
101 {
102 public:
103  // getting aliases from the base class.
107  using Value = typename ExpressionT::Value;
108  using Jacobian = typename ExpressionT::Jacobian;
109  using Hessian = typename ExpressionT::Hessian;
110  using Map = MapT;
111  using Scan = P2DNDTScan;
112  using Point = Eigen::Vector3d;
115  using PointGrad = Eigen::Matrix<float64_t, 3, 6>;
116  using PointHessian = Eigen::Matrix<float64_t, 18, 6>;
117 
129  const P2DNDTScan & scan, const Map & map, const P2DNDTOptimizationConfig config)
130  : m_scan_ref(scan), m_map_ref(map)
131  {
132  init(config.outlier_ratio());
133  }
134 
135  void evaluate_(const DomainValue & x, const ComputeMode & mode)
136  {
137  // Convert pose vector to transform matrix for easy point transformation
138  Eigen::Transform<float64_t, 3, Eigen::Affine, Eigen::ColMajor> transform;
139  transform.setIdentity();
141 
142  Value score{0.0};
143 
145  std::experimental::optional<GradientAngleParameters> grad_params;
146 
148  std::experimental::optional<HessianAngleParameters> hessian_params;
149 
150  {
151  // Angle parameters to be used by all elements (eq. 6.12) [Magnusson 2009]
152  const AngleParameters angle_params{x};
153  // Only construct jacobian/hessian variables if they are needed.
154  if (mode.jacobian() || mode.hessian()) {
155  jacobian.setZero();
156  grad_params.emplace(angle_params);
157  }
158  if (mode.hessian()) {
159  hessian.setZero();
160  hessian_params.emplace(angle_params);
161  }
162  }
163 
164  for (const auto & pt : m_scan_ref) {
165  PointGrad point_gradient;
166  PointHessian point_hessian;
167 
168  if (mode.jacobian() || mode.hessian()) {
169  point_gradient.setZero();
170  point_gradient.block<3, 3>(0, 0).setIdentity();
171  compute_point_gradients(grad_params.value(), pt, point_gradient);
172 
173  if (mode.hessian()) {
174  point_hessian.setZero();
175  compute_point_hessians(hessian_params.value(), pt, point_hessian);
176  }
177  }
178 
179  const Point pt_trans = transform * pt;
180  const auto & cells = m_map_ref.cell(pt_trans);
181 
182  for (const auto & cell : cells) {
183  const Point pt_trans_norm = pt_trans - cell.centroid();
184  // Cell iteration used for compatibility with maps with multi-cell lookup
185  if (!cell.usable()) {
186  continue;
187  }
188  const auto & inv_cov = cell.inverse_covariance();
189  // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
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);
192 
193  if (mode.score()) {
194  score += -m_gauss_d1 * e_minus_half_d2_x_cov_x;
195  }
196 
197  if (!mode.jacobian() && !mode.hessian()) {
198  continue;
199  }
200  const auto d2_e_minus_half_d2_x_cov_x = m_gauss_d2 * e_minus_half_d2_x_cov_x;
201 
202  // Error checking for invalid values.
203  if (!is_valid_probability(d2_e_minus_half_d2_x_cov_x)) {
204  continue;
205  }
206 
207  // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
208  const auto d1_d2_e_minus_half_d2_x_cov_x = m_gauss_d1 * d2_e_minus_half_d2_x_cov_x;
209 
210  for (auto i = 0U; i < jacobian.rows(); ++i) {
211  const Point cov_dxd_pi = inv_cov * point_gradient.col(i);
212  if (mode.jacobian()) {
213  jacobian(i) += pt_trans_norm.dot(cov_dxd_pi) * d1_d2_e_minus_half_d2_x_cov_x;
214  }
215  if (mode.hessian()) {
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));
222  }
223  }
224  }
225  }
226  }
227  if (mode.score()) {
228  this->set_score(score);
229  }
230  if (mode.jacobian()) {
231  this->set_jacobian(jacobian);
232  }
233  if (mode.hessian()) {
234  this->set_hessian(hessian);
235  }
236  }
237 
238 private:
240  struct AngleParameters
241  {
242 public:
243  static constexpr auto approx_thresh{10e-5};
244  AngleParameters() = delete;
245  explicit AngleParameters(const DomainValue & pose)
246  {
247  if (std::fabs(pose(3)) < approx_thresh) {
248  cx = 1.0;
249  sx = 0.0;
250  } else {
251  cx = std::cos(pose(3));
252  sx = std::sin(pose(3));
253  }
254 
255  if (std::fabs(pose(4)) < approx_thresh) {
256  cy = 1.0;
257  sy = 0.0;
258  } else {
259  cy = std::cos(pose(4));
260  sy = std::sin(pose(4));
261  }
262 
263  if (std::fabs(pose(5)) < approx_thresh) {
264  cz = 1.0;
265  sz = 0.0;
266  } else {
267  cz = std::cos(pose(5));
268  sz = std::sin(pose(5));
269  }
270  }
271 
272  Real cx{0.0};
273  Real cy{0.0};
274  Real cz{0.0};
275  Real sx{1.0};
276  Real sy{1.0};
277  Real sz{1.0};
278  };
279 
281  struct GradientAngleParameters
282  {
283 public:
284  GradientAngleParameters() = delete;
285  explicit GradientAngleParameters(const AngleParameters & params)
286  {
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;
290 
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;
294 
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;
298 
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;
302 
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;
306 
307  j_ang_f(0) = -params.cy * params.sz;
308  j_ang_f(1) = -params.cy * params.cz;
309  j_ang_f(2) = 0.0;
310 
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;
313  j_ang_g(2) = 0.0;
314 
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;
317  j_ang_h(2) = 0.0;
318  }
319 
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;
321  };
322 
324  struct HessianAngleParameters
325  {
326 public:
327  HessianAngleParameters() = delete;
328  explicit HessianAngleParameters(const AngleParameters & params)
329  {
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;
333 
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;
337 
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;
341 
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;
345 
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;
348  h_ang_c2(2) = 0.0;
349 
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;
352  h_ang_c3(2) = 0.0;
353 
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;
357 
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;
361 
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;
365 
366  h_ang_e1(0) = params.sy * params.sz;
367  h_ang_e1(1) = params.sy * params.cz;
368  h_ang_e1(2) = 0.0;
369 
370  h_ang_e2(0) = -params.sx * params.cy * params.sz;
371  h_ang_e2(1) = -params.sx * params.cy * params.cz;
372  h_ang_e2(2) = 0.0;
373 
374  h_ang_e3(0) = params.cx * params.cy * params.sz;
375  h_ang_e3(1) = params.cx * params.cy * params.cz;
376  h_ang_e3(2) = 0.0;
377 
378  h_ang_f1(0) = -params.cy * params.cz;
379  h_ang_f1(1) = params.cy * params.sz;
380  h_ang_f1(2) = 0.0;
381 
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;
384  h_ang_f2(2) = 0.0;
385 
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;
388  h_ang_f3(2) = 0.0;
389  }
390 
391  Point h_ang_a2, h_ang_a3,
392  h_ang_b2, h_ang_b3,
393  h_ang_c2, h_ang_c3,
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;
397  };
398 
399  void compute_point_gradients(
400  const GradientAngleParameters & params,
401  const Point & x,
402  PointGrad & point_gradient)
403  {
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);
412  }
413 
414  void compute_point_hessians(
415  const HessianAngleParameters & params,
416  const Point & x,
417  PointHessian & point_hessian)
418  {
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)};
428 
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;
438  }
439 
443  void init(Real outlier_ratio)
444  {
445  if (!is_valid_probability(outlier_ratio)) {
446  throw std::domain_error("Outlier ratio must be between 0 and 1");
447  }
448  const auto c_size = m_map_ref.cell_size();
449  // The gaussian fitting parameters below are taken from the PCL implementation.
450  // 10.0 seems to be a magic number. For details on the gaussian
451  // approximation of the mixture probability in see [Biber et al, 2004] and [Magnusson 2009].
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;
456  m_gauss_d2 = -2 *
457  std::log((-std::log(gauss_c1 * std::exp(-0.5) + gauss_c2) - gauss_d3) / m_gauss_d1);
458  }
459 
460  // references as class members to be initialized at constructor.
461  const Scan & m_scan_ref;
462  const Map & m_map_ref;
463  // States:
464  Real m_gauss_d1{0.0};
465  Real m_gauss_d2{0.0};
466 };
467 
468 template<typename MapT>
470  common::optimization::UnconstrainedOptimizationProblem<P2DNDTObjective<MapT>, EigenPose<Real>,
471  6U>;
472 } // namespace ndt
473 } // namespace localization
474 } // namespace autoware
475 
476 #endif // NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::set_score
void set_score(Value score)
Definition: optimization_problem.hpp:164
autoware::localization::ndt::P2DNDTObjective::Hessian
typename ExpressionT::Hessian Hessian
Definition: ndt_optimization_problem.hpp:109
utils.hpp
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint::value
static constexpr Requires value
Definition: ndt/include/ndt/constraints.hpp:95
types.hpp
This file includes common type definition.
autoware::common::helper_functions::comparisons::abs_lte
bool abs_lte(const T &a, const T &b, const T &eps)
Check for approximate less than or equal in absolute terms.
Definition: float_comparisons.hpp:69
autoware::common::optimization::ComputeMode::jacobian
bool8_t jacobian() const noexcept
Definition: common/optimization/src/utils.cpp:48
ndt_scan.hpp
autoware::common::optimization::ComputeMode
Definition: common/optimization/include/optimization/utils.hpp:38
autoware::localization::ndt::Real
float64_t Real
Definition: ndt_common.hpp:38
utils.hpp
autoware::common::optimization::ComputeMode::hessian
bool8_t hessian() const noexcept
Definition: common/optimization/src/utils.cpp:49
f
DifferentialEquation f
Definition: kinematic_bicycle.snippet.hpp:44
ndt_config.hpp
autoware::localization::ndt::P2DNDTOptimizationProblem
common::optimization::UnconstrainedOptimizationProblem< P2DNDTObjective< MapT >, EigenPose< Real >, 6U > P2DNDTOptimizationProblem
Definition: ndt_optimization_problem.hpp:471
autoware::localization::ndt::P2DNDTObjective::Scan
P2DNDTScan Scan
Definition: ndt_optimization_problem.hpp:111
autoware::common::optimization::EigenComparator
Generic equality comparison functor for eigen matrices.
Definition: common/optimization/include/optimization/utils.hpp:86
autoware::localization::ndt::P2DNDTOptimizationConfig
Config class for p2d optimziation problem.
Definition: ndt_config.hpp:54
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::set_jacobian
void set_jacobian(const JacobianRef &jacobian)
Definition: optimization_problem.hpp:169
autoware::localization::ndt::EigenPose
Eigen::Matrix< T, 6U, 1U > EigenPose
Definition: localization/ndt/include/ndt/utils.hpp:128
autoware::localization::ndt::Requires
Requires
Definition: ndt/include/ndt/constraints.hpp:31
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::P2DNDTScan
Definition: ndt_scan.hpp:101
float_comparisons.hpp
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::set_hessian
void set_hessian(const HessianRef &hessian)
Definition: optimization_problem.hpp:174
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::Jacobian
Eigen::Matrix< Value, NumVars, NumJacobianCols > Jacobian
Definition: optimization_problem.hpp:120
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::Value
autoware::common::types::float64_t Value
Definition: optimization_problem.hpp:119
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::DomainValue
EigenPose< Real > DomainValue
Definition: optimization_problem.hpp:118
autoware::localization::ndt::P2DNDTObjective::PointGrad
Eigen::Matrix< float64_t, 3, 6 > PointGrad
Definition: ndt_optimization_problem.hpp:115
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::Hessian
Eigen::Matrix< Value, NumVars, NumVars > Hessian
Definition: optimization_problem.hpp:121
x
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
autoware::localization::ndt::P2DNDTObjective::P2DNDTObjective
P2DNDTObjective(const P2DNDTScan &scan, const Map &map, const P2DNDTOptimizationConfig config)
Definition: ndt_optimization_problem.hpp:128
autoware::localization::ndt::P2DNDTObjective::Value
typename ExpressionT::Value Value
Definition: ndt_optimization_problem.hpp:107
autoware::localization::ndt::P2DNDTOptimizationConfig::outlier_ratio
Real outlier_ratio() const noexcept
Definition: ndt_config.hpp:65
autoware::localization::ndt::transform_adapters::pose_to_transform
void pose_to_transform(const PoseT &pose, TransformT &transform)
autoware::localization::ndt::P2DNDTObjective::PointHessian
Eigen::Matrix< float64_t, 18, 6 > PointHessian
Definition: ndt_optimization_problem.hpp:116
optimization_problem.hpp
autoware::localization::ndt::P2DNDTObjective::Jacobian
typename ExpressionT::Jacobian Jacobian
Definition: ndt_optimization_problem.hpp:108
autoware::common::optimization::CachedExpression
Definition: optimization_problem.hpp:109
autoware::common::helper_functions::comparisons::abs_gte
bool abs_gte(const T &a, const T &b, const T &eps)
Check for approximate greater than or equal in absolute terms.
Definition: float_comparisons.hpp:80
autoware::localization::ndt::P2DNDTObjective
Definition: ndt_optimization_problem.hpp:99
autoware::localization::ndt::P2DNDTObjective::Map
MapT Map
Definition: ndt_optimization_problem.hpp:110
Point
geometry_msgs::msg::Point32 Point
Definition: cluster2d.cpp:28
ndt_map.hpp
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::localization::ndt::is_valid_probability
bool8_t is_valid_probability(ScalarT p)
Definition: ndt_optimization_problem.hpp:85
autoware::localization::ndt::P2DNDTObjective::evaluate_
void evaluate_(const DomainValue &x, const ComputeMode &mode)
Definition: ndt_optimization_problem.hpp:135
autoware::common::optimization::Expression< CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, NumJacobianColsT, NumVarsT, common::optimization::EigenComparator >, EigenPose< Real >, NumJacobianColsT, NumVarsT >::jacobian
void jacobian(const DomainValue &x, JacobianRef out)
Definition: optimization_problem.hpp:69
autoware::localization::ndt::P2DNDTObjective::Point
Eigen::Vector3d Point
Definition: ndt_optimization_problem.hpp:112
autoware::localization::ndt::P2DNDTObjective::DomainValue
typename ExpressionT::DomainValue DomainValue
Definition: ndt_optimization_problem.hpp:106
autoware::common::optimization::Expression< CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, NumJacobianColsT, NumVarsT, common::optimization::EigenComparator >, EigenPose< Real >, NumJacobianColsT, NumVarsT >::hessian
void hessian(const DomainValue &x, HessianRef out)
Definition: optimization_problem.hpp:77
autoware::common::optimization::ComputeMode::score
bool8_t score() const noexcept
Definition: common/optimization/src/utils.cpp:47
constraints.hpp