Generic interface for solver implementations. More...
#include <nlp_solver_interface.h>
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... | |
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:
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.
Definition at line 67 of file nlp_solver_interface.h.
using corbo::NlpSolverInterface::Ptr = std::shared_ptr<NlpSolverInterface> |
Definition at line 70 of file nlp_solver_interface.h.
using corbo::NlpSolverInterface::UPtr = std::unique_ptr<NlpSolverInterface> |
Definition at line 71 of file nlp_solver_interface.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 74 of file nlp_solver_interface.h.
|
pure virtual |
Clear internal caches.
Implemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.
|
pure virtual |
Return a newly created instance of the current solver.
Implemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.
|
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.
[in] | problem | Optimization problem definition with possibly incomplete structure [optional] |
Reimplemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.
Definition at line 92 of file nlp_solver_interface.h.
|
pure virtual |
Return true if the solver onyl supports costs in lsq form.
Implemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.
|
pure virtual |
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] |
Implemented in corbo::SolverIpopt, corbo::LevenbergMarquardtSparse, and corbo::LevenbergMarquardtDense.