Optimizer using the Newton method with line search.
More...
#include <newtons_method_optimizer.hpp>
|
const NewtonsMethodOptimizer< LineSearchT > & | impl () const |
|
NewtonsMethodOptimizer< LineSearchT > & | impl () |
|
template<typename LineSearchT>
class autoware::common::optimization::NewtonsMethodOptimizer< LineSearchT >
Optimizer using the Newton method with line search.
◆ StepT
template<typename LineSearchT >
◆ NewtonsMethodOptimizer()
template<typename LineSearchT >
Constructor to initialize the line search method
- Parameters
-
[in] | line_searcher | An instance of a line search class. |
[in] | options | Options to be used for this optimization. |
◆ solve_()
template<typename LineSearchT >
template<typename OptimizationProblemT , typename DomainValueT , typename EigenSolverT >
Solves x_out
for an objective optimization_problem
and an initial value x0
- Parameters
-
optimization_problem | optimization_problem optimization objective |
x0 | initial value |
x_out | optimized value |
- Template Parameters
-
OptimizationProblemT | Optimization problem type. Must be an implementation of common::optimization::OptimizationProblem . |
DomainValueT | Type of the parameter |
EigenSolverT | Type of eigen solver to be used internallt for solving the necessary linear equations. By default set to Eigen::LDLT . |
- Returns
- Summary of this optimization.
The documentation for this class was generated from the following file: