Interface to the external interior point solver IPOPT. More...
#include <nlp_solver_ipopt.h>
Public Types | |
enum | LinearSolver { LinearSolver::MUMPS, LinearSolver::MA27, LinearSolver::MA57, LinearSolver::MA77, LinearSolver::MA86, LinearSolver::MA97, LinearSolver::NO_SOLVER } |
using | Ptr = std::shared_ptr< SolverIpopt > |
using | UPtr = std::unique_ptr< SolverIpopt > |
![]() | |
using | Ptr = std::shared_ptr< NlpSolverInterface > |
using | UPtr = std::unique_ptr< NlpSolverInterface > |
Public Member Functions | |
void | clear () override |
Clear internal caches. More... | |
NlpSolverInterface::Ptr | getInstance () const override |
Return a newly created instance of the current solver. More... | |
bool | initialize (OptimizationProblemInterface *problem=nullptr) override |
Initialize the solver w.r.t. a given optimization problem. More... | |
bool | isLsqSolver () const override |
Return true if the solver onyl supports costs in lsq form. More... | |
SolverStatus | solve (OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override |
Solve the provided optimization problem. More... | |
![]() | |
virtual | ~NlpSolverInterface () |
Virtual destructor. More... | |
Protected Member Functions | |
void | printWarning () const |
Interface to the external interior point solver IPOPT.
Definition at line 188 of file nlp_solver_ipopt.h.
using corbo::SolverIpopt::Ptr = std::shared_ptr<SolverIpopt> |
Definition at line 191 of file nlp_solver_ipopt.h.
using corbo::SolverIpopt::UPtr = std::unique_ptr<SolverIpopt> |
Definition at line 192 of file nlp_solver_ipopt.h.
|
strong |
Enumerator | |
---|---|
MUMPS | |
MA27 | |
MA57 | |
MA77 | |
MA86 | |
MA97 | |
NO_SOLVER |
Definition at line 194 of file nlp_solver_ipopt.h.
|
inlineoverridevirtual |
Clear internal caches.
Implements corbo::NlpSolverInterface.
Definition at line 215 of file nlp_solver_ipopt.h.
|
inlineoverridevirtual |
Return a newly created instance of the current solver.
Implements corbo::NlpSolverInterface.
Definition at line 197 of file nlp_solver_ipopt.h.
|
inlineoverridevirtual |
Initialize the solver w.r.t. a given optimization problem.
The structure of the optimization problem might be still subject to change when calling this method. However, this method can be used to preallocate some memory and to check general features of the provided optimization problem, e.g. if Jacobian and Hessian matrices are available.
[in] | problem | Optimization problem definition with possibly incomplete structure [optional] |
Reimplemented from corbo::NlpSolverInterface.
Definition at line 203 of file nlp_solver_ipopt.h.
|
inlineoverridevirtual |
Return true if the solver onyl supports costs in lsq form.
Implements corbo::NlpSolverInterface.
Definition at line 200 of file nlp_solver_ipopt.h.
|
inlineprotected |
Definition at line 229 of file nlp_solver_ipopt.h.
|
inlineoverridevirtual |
Solve the provided optimization problem.
[in,out] | problem | Optimization problem definition, pre-solving: object contains the initial parameter set post-solving: object contains the optimized parameter set |
[in] | new_structure | true if one of the dimensions or non-zero patterns has changed. |
[in] | new_run | true if a new optimization run (not just an iteration) is performed, e.g. to reset possible weight adaptation strategies etc. |
[out] | obj_value | Returns the resulting objective function value [optional] |
Implements corbo::NlpSolverInterface.
Definition at line 209 of file nlp_solver_ipopt.h.