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 
59 #include <ndt/ndt_map.hpp>
60 #include <ndt/ndt_scan.hpp>
61 #include <ndt/ndt_config.hpp>
63 #include <optimization/utils.hpp>
64 #include <ndt/utils.hpp>
65 #include <experimental/optional>
66 #include <Eigen/Core>
67 #include <Eigen/Geometry>
68 #include <tuple>
69 #include "common/types.hpp"
70 
73 
74 namespace autoware
75 {
76 namespace localization
77 {
78 namespace ndt
79 {
80 
81 template<typename ScalarT>
83 {
84  bool8_t ret = true;
85  if (std::isnan(p) || p > ScalarT{1.0} || p < ScalarT{0.0}) {
86  ret = false;
87  }
88  return ret;
89 }
90 
94 template<typename MapT>
95 class P2DNDTObjective : public common::optimization::CachedExpression<P2DNDTObjective<MapT>,
96  EigenPose<Real>, 1U, 6U, common::optimization::EigenComparator>
97 {
98 public:
99  // getting aliases from the base class.
103  using Value = typename ExpressionT::Value;
104  using Jacobian = typename ExpressionT::Jacobian;
105  using Hessian = typename ExpressionT::Hessian;
106  using Map = MapT;
107  using Scan = P2DNDTScan;
108  using Point = typename Map::Point;
111  using PointGrad = Eigen::Matrix<float64_t, 3, 6>;
112  using PointHessian = Eigen::Matrix<float64_t, 18, 6>;
113 
125  const P2DNDTScan & scan, const Map & map, const P2DNDTOptimizationConfig config)
126  : m_scan_ref(scan), m_map_ref(map)
127  {
128  init(config.outlier_ratio());
129  }
130 
131  void evaluate_(const DomainValue & x, const ComputeMode & mode)
132  {
133  // Convert pose vector to transform matrix for easy point transformation
134  Eigen::Transform<float64_t, 3, Eigen::Affine, Eigen::ColMajor> transform;
135  transform.setIdentity();
137 
138  Value score{0.0};
139 
141  std::experimental::optional<GradientAngleParameters> grad_params;
142 
144  std::experimental::optional<HessianAngleParameters> hessian_params;
145 
146  {
147  // Angle parameters to be used by all elements (eq. 6.12) [Magnusson 2009]
148  const AngleParameters angle_params{x};
149  // Only construct jacobian/hessian variables if they are needed.
150  if (mode.jacobian() || mode.hessian()) {
151  jacobian.setZero();
152  grad_params.emplace(angle_params);
153  }
154  if (mode.hessian()) {
155  hessian.setZero();
156  hessian_params.emplace(angle_params);
157  }
158  }
159 
160  for (const auto & pt : m_scan_ref) {
161  PointGrad point_gradient;
162  PointHessian point_hessian;
163 
164  if (mode.jacobian() || mode.hessian()) {
165  point_gradient.setZero();
166  point_gradient.block<3, 3>(0, 0).setIdentity();
167  compute_point_gradients(grad_params.value(), pt, point_gradient);
168 
169  if (mode.hessian()) {
170  point_hessian.setZero();
171  compute_point_hessians(hessian_params.value(), pt, point_hessian);
172  }
173  }
174 
175  const Point pt_trans = transform * pt;
176  const auto & cells = m_map_ref.cell(pt_trans);
177 
178  for (const auto & cell : cells) {
179  const Point pt_trans_norm = pt_trans - cell.centroid();
180  // Cell iteration used for compatibility with maps with multi-cell lookup
181  if (cell.usable()) {
182  const auto & inv_cov = cell.inverse_covariance();
183  // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
184  Real e_x_cov_x = std::exp(
185  -m_gauss_d2 * pt_trans_norm.dot(
186  inv_cov * pt_trans_norm) / 2.0);
187 
188  if (mode.score()) {
189  score += -m_gauss_d1 * e_x_cov_x;
190  }
191 
192  if (mode.jacobian() || mode.hessian()) {
193  const auto d2_e_x_cov_x = m_gauss_d2 * e_x_cov_x;
194 
195  // Error checking for invalid values.
196  // TODO(yunus.caliskan): Can be removed after covariance is checked
197  // for definiteness #216
198  if (!is_valid_probability(d2_e_x_cov_x)) {
199  continue;
200  }
201 
202  // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
203  const auto d1_d2_e_x_cov_x = m_gauss_d1 * d2_e_x_cov_x;
204 
205  for (auto i = 0U; i < jacobian.rows(); ++i) {
206  const Point cov_dxd_pi = inv_cov * point_gradient.col(i);
207  if (mode.jacobian()) {
208  jacobian(i) += pt_trans_norm.dot(cov_dxd_pi) * d1_d2_e_x_cov_x;
209  }
210  if (mode.hessian()) {
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));
216  }
217  }
218  }
219  }
220  }
221  }
222  }
223  if (mode.score()) {
224  this->set_score(score);
225  }
226  if (mode.jacobian()) {
227  this->set_jacobian(jacobian);
228  }
229  if (mode.hessian()) {
230  this->set_hessian(hessian);
231  }
232  }
233 
234 private:
236  struct AngleParameters
237  {
238 public:
239  static constexpr auto approx_thresh{10e-5};
240  AngleParameters() = delete;
241  explicit AngleParameters(const DomainValue & pose)
242  {
243  if (std::fabs(pose(3)) < approx_thresh) {
244  cx = 1.0;
245  sx = 0.0;
246  } else {
247  cx = std::cos(pose(3));
248  sx = std::sin(pose(3));
249  }
250 
251  if (std::fabs(pose(4)) < approx_thresh) {
252  cy = 1.0;
253  sy = 0.0;
254  } else {
255  cy = std::cos(pose(4));
256  sy = std::sin(pose(4));
257  }
258 
259  if (std::fabs(pose(5)) < approx_thresh) {
260  cz = 1.0;
261  sz = 0.0;
262  } else {
263  cz = std::cos(pose(5));
264  sz = std::sin(pose(5));
265  }
266  }
267 
268  Real cx{0.0};
269  Real cy{0.0};
270  Real cz{0.0};
271  Real sx{1.0};
272  Real sy{1.0};
273  Real sz{1.0};
274  };
275 
277  struct GradientAngleParameters
278  {
279 public:
280  GradientAngleParameters() = delete;
281  explicit GradientAngleParameters(const AngleParameters & params)
282  {
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;
286 
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;
290 
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;
294 
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;
298 
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;
302 
303  j_ang_f(0) = -params.cy * params.sz;
304  j_ang_f(1) = -params.cy * params.cz;
305  j_ang_f(2) = 0.0;
306 
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;
309  j_ang_g(2) = 0.0;
310 
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;
313  j_ang_h(2) = 0.0;
314  }
315 
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;
317  };
318 
320  struct HessianAngleParameters
321  {
322 public:
323  HessianAngleParameters() = delete;
324  explicit HessianAngleParameters(const AngleParameters & params)
325  {
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;
329 
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;
333 
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;
337 
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;
341 
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;
344  h_ang_c2(2) = 0.0;
345 
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;
348  h_ang_c3(2) = 0.0;
349 
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;
353 
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;
357 
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;
361 
362  h_ang_e1(0) = params.sy * params.sz;
363  h_ang_e1(1) = params.sy * params.cz;
364  h_ang_e1(2) = 0.0;
365 
366  h_ang_e2(0) = -params.sx * params.cy * params.sz;
367  h_ang_e2(1) = -params.sx * params.cy * params.cz;
368  h_ang_e2(2) = 0.0;
369 
370  h_ang_e3(0) = params.cx * params.cy * params.sz;
371  h_ang_e3(1) = params.cx * params.cy * params.cz;
372  h_ang_e3(2) = 0.0;
373 
374  h_ang_f1(0) = -params.cy * params.cz;
375  h_ang_f1(1) = params.cy * params.sz;
376  h_ang_f1(2) = 0.0;
377 
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;
380  h_ang_f2(2) = 0.0;
381 
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;
384  h_ang_f3(2) = 0.0;
385  }
386 
387  Point h_ang_a2, h_ang_a3,
388  h_ang_b2, h_ang_b3,
389  h_ang_c2, h_ang_c3,
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;
393  };
394 
395  void compute_point_gradients(
396  const GradientAngleParameters & params,
397  const Point & x,
398  PointGrad & point_gradient)
399  {
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);
408  }
409 
410  void compute_point_hessians(
411  const HessianAngleParameters & params,
412  const Point & x,
413  PointHessian & point_hessian)
414  {
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)};
424 
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;
434  }
435 
439  void init(Real outlier_ratio)
440  {
441  if (!is_valid_probability(outlier_ratio)) {
442  throw std::domain_error("Outlier ratio must be between 0 and 1");
443  }
444  const auto c_size = m_map_ref.cell_size();
445  // The gaussian fitting parameters below are taken from the PCL implementation.
446  // 10.0 seems to be a magic number. For details on the gaussian
447  // approximation of the mixture probability in see [Biber et al, 2004] and [Magnusson 2009].
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;
452  m_gauss_d2 = -2 *
453  std::log((-std::log(gauss_c1 * std::exp(-0.5) + gauss_c2) - gauss_d3) / m_gauss_d1);
454  }
455 
456  // references as class members to be initialized at constructor.
457  const Scan & m_scan_ref;
458  const Map & m_map_ref;
459  // States:
460  Real m_gauss_d1{0.0};
461  Real m_gauss_d2{0.0};
462 };
463 
464 template<typename MapT>
466  common::optimization::UnconstrainedOptimizationProblem<P2DNDTObjective<MapT>, EigenPose<Real>,
467  6U>;
468 } // namespace ndt
469 } // namespace localization
470 } // namespace autoware
471 
472 #endif // NDT__NDT_OPTIMIZATION_PROBLEM_HPP_
autoware::localization::ndt::P2DNDTObjective::Point
typename Map::Point Point
Definition: ndt_optimization_problem.hpp:108
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::set_score
void set_score(Value score)
Definition: optimization_problem.hpp:163
utils.hpp
types.hpp
This file includes common type definition.
autoware::common::optimization::ComputeMode::jacobian
bool8_t jacobian() const noexcept
Definition: utils.cpp:48
ndt_scan.hpp
autoware::common::optimization::ComputeMode
Definition: common/optimization/include/optimization/utils.hpp:38
autoware::localization::ndt::P2DNDTObjective::Scan
P2DNDTScan Scan
Definition: ndt_optimization_problem.hpp:107
autoware::localization::ndt::Real
float64_t Real
Definition: ndt_common.hpp:39
utils.hpp
autoware::localization::ndt::P2DNDTObjective::P2DNDTObjective
P2DNDTObjective(const P2DNDTScan &scan, const Map &map, const P2DNDTOptimizationConfig config)
Definition: ndt_optimization_problem.hpp:124
autoware::localization::ndt::P2DNDTObjective::Map
MapT Map
Definition: ndt_optimization_problem.hpp:106
autoware::common::optimization::ComputeMode::hessian
bool8_t hessian() const noexcept
Definition: utils.cpp:49
autoware::common::geometry::Point
geometry_msgs::msg::Point32 Point
Definition: intersection.hpp:52
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:467
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:80
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
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:168
autoware::localization::ndt::EigenPose
Eigen::Matrix< T, 6U, 1U > EigenPose
Definition: localization/ndt/include/ndt/utils.hpp:83
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::P2DNDTScan
Definition: ndt_scan.hpp:99
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:173
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::Jacobian
Eigen::Matrix< Value, NumVars, NumJacobianCols > Jacobian
Definition: optimization_problem.hpp:119
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::Value
autoware::common::types::float64_t Value
Definition: optimization_problem.hpp:118
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::DomainValue
EigenPose< Real > DomainValue
Definition: optimization_problem.hpp:117
autoware::common::optimization::CachedExpression< P2DNDTObjective< MapT >, EigenPose< Real >, 1U, 6U, common::optimization::EigenComparator >::Hessian
Eigen::Matrix< Value, NumVars, NumVars > Hessian
Definition: optimization_problem.hpp:120
x
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
autoware::localization::ndt::P2DNDTObjective::Jacobian
typename ExpressionT::Jacobian Jacobian
Definition: ndt_optimization_problem.hpp:104
autoware::localization::ndt::P2DNDTObjective::DomainValue
typename ExpressionT::DomainValue DomainValue
Definition: ndt_optimization_problem.hpp:102
catr_diff.a
a
Definition: catr_diff.py:22
autoware::localization::ndt::P2DNDTOptimizationConfig::outlier_ratio
Real outlier_ratio() const noexcept
Definition: ndt_config.hpp:91
autoware::localization::ndt::transform_adapters::pose_to_transform
void pose_to_transform(const PoseT &pose, TransformT &transform)
autoware::localization::ndt::P2DNDTObjective::PointGrad
Eigen::Matrix< float64_t, 3, 6 > PointGrad
Definition: ndt_optimization_problem.hpp:111
optimization_problem.hpp
autoware::localization::ndt::P2DNDTObjective::Hessian
typename ExpressionT::Hessian Hessian
Definition: ndt_optimization_problem.hpp:105
autoware::common::optimization::CachedExpression
Definition: optimization_problem.hpp:109
autoware::localization::ndt::P2DNDTObjective
Definition: ndt_optimization_problem.hpp:95
autoware::localization::ndt::P2DNDTObjective::Value
typename ExpressionT::Value Value
Definition: ndt_optimization_problem.hpp:103
autoware::localization::ndt::P2DNDTObjective::evaluate_
void evaluate_(const DomainValue &x, const ComputeMode &mode)
Definition: ndt_optimization_problem.hpp:131
ndt_map.hpp
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:37
autoware::localization::ndt::is_valid_probability
bool8_t is_valid_probability(ScalarT p)
Definition: ndt_optimization_problem.hpp:82
autoware::localization::ndt::P2DNDTObjective::PointHessian
Eigen::Matrix< float64_t, 18, 6 > PointHessian
Definition: ndt_optimization_problem.hpp:112
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::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: utils.cpp:47