Go to the documentation of this file.
25 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_SPARSE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_SPARSE_H_
30 #include <Eigen/Sparse>
33 #include <Eigen/CholmodSupport>
68 class LevenbergMarquardtSparse :
public NlpSolverInterface
71 using Ptr = std::shared_ptr<LevenbergMarquardtSparse>;
72 using UPtr = std::unique_ptr<LevenbergMarquardtSparse>;
81 bool initialize(OptimizationProblemInterface* problem =
nullptr)
override;
83 SolverStatus solve(OptimizationProblemInterface& problem,
bool new_structure =
true,
bool new_run =
true,
double* obj_value =
nullptr)
override;
88 void setPenaltyWeights(
double weight_eq,
double weight_ineq,
double weight_bounds);
90 void setWeightAdapation(
double factor_eq,
double factor_ineq,
double factor_bounds,
double max_eq,
double max_ineq,
double max_bounds);
92 void clear()
override;
94 #ifdef MESSAGE_SUPPORT
96 void toMessage(corbo::messages::NlpSolver& message)
const override;
98 void fromMessage(
const corbo::messages::NlpSolver& message, std::stringstream* issues =
nullptr)
override;
138 Eigen::VectorXd
_rhs;
151 #if defined(CHOLMOD) && !defined(FORCE_EIGEN_SOLVER)
163 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_SPARSE_H_
double _weight_adapt_factor_eq
Levenberg-Marquardt Solver (Sparse matrices version).
std::unique_ptr< LevenbergMarquardtSparse > UPtr
std::shared_ptr< LevenbergMarquardtSparse > Ptr
void computeValues(OptimizationProblemInterface &problem)
Compute overall value vector including constraint approximation.
double _weight_adapt_factor_ineq
void clear() override
Clear internal caches.
void resetWeights()
Reset weights to their original values.
bool isLsqSolver() const override
Return true if the solver onyl supports costs in lsq form.
A direct sparse LLT Cholesky factorizations.
std::shared_ptr< NlpSolverInterface > Ptr
Eigen::SparseMatrix< double > _jacobian
void adaptWeights()
Perform single weight adapation step.
void setPenaltyWeights(double weight_eq, double weight_ineq, double weight_bounds)
Define penalty weights (equality constraints, inequality constraints, bounds)
double _weight_adapt_max_bounds
void setIterations(int iterations)
Define the number of solver iterations.
double _weight_adapt_factor_bounds
double _weight_adapt_max_eq
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.
double _weight_adapt_max_ineq
A supernodal Cholesky (LLT) factorization and solver based on Cholmod.
SolverStatus solve(OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override
Solve the provided optimization problem.
void setWeightAdapation(double factor_eq, double factor_ineq, double factor_bounds, double max_eq, double max_ineq, double max_bounds)
Set parameters for weight adaptation (refer to the class description); set factors to 1 in order to d...
NlpSolverInterface::Ptr getInstance() const override
Return a newly created instance of the current solver.
#define FACTORY_REGISTER_NLP_SOLVER(type)
Eigen::SimplicialLLT< Eigen::SparseMatrix< double >, Eigen::Upper > _sparse_solver
Eigens sparse solver wrapper. Check http://eigen.tuxfamily.org/dox/group__TopicSparseSystems....
Eigen::SparseMatrix< double > _hessian
double _weight_init_bounds
Generic interface for optimization problem definitions.
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:52