Autoware.Auto
optimizer_options.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 #ifndef OPTIMIZATION__OPTIMIZER_OPTIONS_HPP_
18 #define OPTIMIZATION__OPTIMIZER_OPTIONS_HPP_
19 
20 #include <common/types.hpp>
22 #include <limits>
23 #include <cstdint>
24 
26 
27 namespace autoware
28 {
29 namespace common
30 {
31 namespace optimization
32 {
34 enum class TerminationType
35 {
36  // Optimizer could converge according to the criteria specified in the used
37  CONVERGENCE = 0U,
38  // Optimizer finished without reaching convergence.
39  NO_CONVERGENCE = 1U,
40  // An error occurred during optimization and the result is not usable.
41  // Usually indicates a numerical issue.
42  FAILURE = 2U
43 };
44 
45 // Optimization options class for newton's method.
46 class OPTIMIZATION_PUBLIC OptimizationOptions
47 {
48 public:
56  uint64_t max_num_iterations = std::numeric_limits<int64_t>::max(),
57  float64_t function_tolerance = 0.0, float64_t parameter_tolerance = 0.0,
58  float64_t gradient_tolerance = 0.0);
59 
61  uint64_t max_num_iterations() const noexcept;
63  float64_t function_tolerance() const noexcept;
65  float64_t parameter_tolerance() const noexcept;
67  float64_t gradient_tolerance() const noexcept;
68 
69 private:
70  uint64_t m_max_num_iterations;
71  float64_t m_function_tolerance;
72  float64_t m_parameter_tolerance;
73  float64_t m_gradient_tolerance;
74 };
75 
76 // Optimization summary class.
77 class OPTIMIZATION_PUBLIC OptimizationSummary
78 {
79 public:
84  OptimizationSummary(float64_t dist, TerminationType termination_type, uint64_t iter);
85 
87  float64_t estimated_distance_to_optimum() const noexcept;
89  TerminationType termination_type() const noexcept;
91  uint64_t number_of_iterations_made() const noexcept;
92 
93 private:
94  float64_t m_estimated_distance_to_optimum;
95  uint64_t m_number_of_iterations_made;
96  TerminationType m_termination_type;
97 };
98 
99 } // namespace optimization
100 } // namespace common
101 } // namespace autoware
102 
103 #endif // OPTIMIZATION__OPTIMIZER_OPTIONS_HPP_
types.hpp
This file includes common type definition.
autoware::common::optimization::TerminationType::CONVERGENCE
@ CONVERGENCE
autoware::common::optimization::OptimizationSummary
Definition: optimizer_options.hpp:77
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::optimization::TerminationType::FAILURE
@ FAILURE
visibility_control.hpp
autoware::common::optimization::OptimizationOptions
Definition: optimizer_options.hpp:46
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::common::optimization::TerminationType::NO_CONVERGENCE
@ NO_CONVERGENCE
autoware::common::optimization::TerminationType
TerminationType
Type of termination at the end of an optimization loop.
Definition: optimizer_options.hpp:34