Public Types | Public Member Functions | Protected Member Functions | List of all members
corbo::SolverIpopt Class Reference

Interface to the external interior point solver IPOPT. More...

#include <nlp_solver_ipopt.h>

Inheritance diagram for corbo::SolverIpopt:
Inheritance graph
[legend]

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 >
 
- Public Types inherited from corbo::NlpSolverInterface
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...
 
- Public Member Functions inherited from corbo::NlpSolverInterface
virtual ~NlpSolverInterface ()
 Virtual destructor. More...
 

Protected Member Functions

void printWarning () const
 

Detailed Description

Interface to the external interior point solver IPOPT.

Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)

Definition at line 188 of file nlp_solver_ipopt.h.

Member Typedef Documentation

◆ Ptr

using corbo::SolverIpopt::Ptr = std::shared_ptr<SolverIpopt>

Definition at line 191 of file nlp_solver_ipopt.h.

◆ UPtr

using corbo::SolverIpopt::UPtr = std::unique_ptr<SolverIpopt>

Definition at line 192 of file nlp_solver_ipopt.h.

Member Enumeration Documentation

◆ LinearSolver

Enumerator
MUMPS 
MA27 
MA57 
MA77 
MA86 
MA97 
NO_SOLVER 

Definition at line 194 of file nlp_solver_ipopt.h.

Member Function Documentation

◆ clear()

void corbo::SolverIpopt::clear ( )
inlineoverridevirtual

Clear internal caches.

Implements corbo::NlpSolverInterface.

Definition at line 215 of file nlp_solver_ipopt.h.

◆ getInstance()

NlpSolverInterface::Ptr corbo::SolverIpopt::getInstance ( ) const
inlineoverridevirtual

Return a newly created instance of the current solver.

Implements corbo::NlpSolverInterface.

Definition at line 197 of file nlp_solver_ipopt.h.

◆ initialize()

bool corbo::SolverIpopt::initialize ( OptimizationProblemInterface problem = nullptr)
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.

Parameters
[in]problemOptimization problem definition with possibly incomplete structure [optional]
Returns
true if the sovler seems to be suited, false otherwise.

Reimplemented from corbo::NlpSolverInterface.

Definition at line 203 of file nlp_solver_ipopt.h.

◆ isLsqSolver()

bool corbo::SolverIpopt::isLsqSolver ( ) const
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.

◆ printWarning()

void corbo::SolverIpopt::printWarning ( ) const
inlineprotected

Definition at line 229 of file nlp_solver_ipopt.h.

◆ solve()

SolverStatus corbo::SolverIpopt::solve ( OptimizationProblemInterface problem,
bool  new_structure = true,
bool  new_run = true,
double *  obj_value = nullptr 
)
inlineoverridevirtual

Solve the provided optimization problem.

Parameters
[in,out]problemOptimization problem definition, pre-solving: object contains the initial parameter set post-solving: object contains the optimized parameter set
[in]new_structuretrue if one of the dimensions or non-zero patterns has changed.
[in]new_runtrue if a new optimization run (not just an iteration) is performed, e.g. to reset possible weight adaptation strategies etc.
[out]obj_valueReturns the resulting objective function value [optional]
Returns
Solver status as indicated above

Implements corbo::NlpSolverInterface.

Definition at line 209 of file nlp_solver_ipopt.h.


The documentation for this class was generated from the following file:


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03