Public Types | Public Member Functions | List of all members
corbo::NlpSolverInterface Class Referenceabstract

Generic interface for solver implementations. More...

#include <nlp_solver_interface.h>

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

Public Types

using Ptr = std::shared_ptr< NlpSolverInterface >
 
using UPtr = std::unique_ptr< NlpSolverInterface >
 

Public Member Functions

virtual void clear ()=0
 Clear internal caches. More...
 
virtual Ptr getInstance () const =0
 Return a newly created instance of the current solver. More...
 
virtual bool initialize (OptimizationProblemInterface *problem=nullptr)
 Initialize the solver w.r.t. a given optimization problem. More...
 
virtual bool isLsqSolver () const =0
 Return true if the solver onyl supports costs in lsq form. More...
 
virtual SolverStatus solve (OptimizationProblemInterface &problem, bool new_structure, bool new_run=true, double *obj_value=nullptr)=0
 Solve the provided optimization problem. More...
 
virtual ~NlpSolverInterface ()
 Virtual destructor. More...
 

Detailed Description

Generic interface for solver implementations.

This class can be used to generically define solver back-ends for optimization problems with objectives, equality constraints, inequality constraints, box constraints and their current parameter state:

\[ \min f(x), \ f : \mathbb{R}^n \to \mathbb{R}^m \\ \text{subject to:} \\ ceq(x) = 0 \\ c(x) < 0 \\ lb < x < ub \]

The optimization problem is usually defined in terms of an OptimizationProblemInterface instance and the solver needs to check whether 1st and/or 2nd order derivatives in dense or sparse form are required.

See also
OptimizationProblemInterface
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 67 of file nlp_solver_interface.h.

Member Typedef Documentation

◆ Ptr

Definition at line 70 of file nlp_solver_interface.h.

◆ UPtr

Definition at line 71 of file nlp_solver_interface.h.

Constructor & Destructor Documentation

◆ ~NlpSolverInterface()

virtual corbo::NlpSolverInterface::~NlpSolverInterface ( )
inlinevirtual

Virtual destructor.

Definition at line 74 of file nlp_solver_interface.h.

Member Function Documentation

◆ clear()

virtual void corbo::NlpSolverInterface::clear ( )
pure virtual

◆ getInstance()

virtual Ptr corbo::NlpSolverInterface::getInstance ( ) const
pure virtual

Return a newly created instance of the current solver.

Implemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.

◆ initialize()

virtual bool corbo::NlpSolverInterface::initialize ( OptimizationProblemInterface problem = nullptr)
inlinevirtual

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 in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.

Definition at line 92 of file nlp_solver_interface.h.

◆ isLsqSolver()

virtual bool corbo::NlpSolverInterface::isLsqSolver ( ) const
pure virtual

Return true if the solver onyl supports costs in lsq form.

Implemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.

◆ solve()

virtual SolverStatus corbo::NlpSolverInterface::solve ( OptimizationProblemInterface problem,
bool  new_structure,
bool  new_run = true,
double *  obj_value = nullptr 
)
pure virtual

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

Implemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.


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