Autoware.Auto
optimizer.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_HPP_
18 #define OPTIMIZATION__OPTIMIZER_HPP_
19 
22 #include <Eigen/SVD>
23 
24 namespace autoware
25 {
26 namespace common
27 {
28 namespace optimization
29 {
30 // Optimization solver base class(CRTP) for a given optimization problem.
31 template<typename Derived>
32 class OPTIMIZATION_PUBLIC Optimizer : public common::helper_functions::crtp<Derived>
33 {
34 public:
45  template<
46  typename OptimizationProblemT,
47  typename DomainValueT,
48  typename EigenSolverT = Eigen::LDLT<typename OptimizationProblemT::Hessian>>
50  OptimizationProblemT & optimization_problem,
51  const DomainValueT & x0,
52  DomainValueT & x_out)
53  {
54  return this->impl().template solve_<OptimizationProblemT, DomainValueT, EigenSolverT>(
55  optimization_problem, x0, x_out);
56  }
57 };
58 
59 } // namespace optimization
60 } // namespace common
61 } // namespace autoware
62 
63 #endif // OPTIMIZATION__OPTIMIZER_HPP_
OptimizationSummary solve(OptimizationProblemT &optimization_problem, const DomainValueT &x0, DomainValueT &x_out)
Definition: optimizer.hpp:49
Definition: optimizer_options.hpp:77
Definition: optimizer.hpp:32
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24