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> 71 using Ptr = std::shared_ptr<LevenbergMarquardtSparse>;
72 using UPtr = std::unique_ptr<LevenbergMarquardtSparse>;
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;
151 #if defined(CHOLMOD) && !defined(FORCE_EIGEN_SOLVER) 163 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_SPARSE_H_
void setIterations(int iterations)
Define the number of solver iterations.
Eigen::SparseMatrix< double > _hessian
NlpSolverInterface::Ptr getInstance() const override
Return a newly created instance of the current solver.
void resetWeights()
Reset weights to their original values.
A supernodal Cholesky (LLT) factorization and solver based on Cholmod.
double _weight_init_bounds
double _weight_adapt_max_bounds
Eigen::SimplicialLLT< Eigen::SparseMatrix< double >, Eigen::Upper > _sparse_solver
Eigens sparse solver wrapper. Check http://eigen.tuxfamily.org/dox/group__TopicSparseSystems.html for further information and different solvers. The second template parameter specifies, whether the upper or lower triangular part should be used. If CHOLMOD was found by CMake, the cholmod supernodal llt version is used rathar than Eigens simplicial ldlt. Define FORCE_EIGEN_SOLVER if the default LDLT should sill be used even if CHOLMOD is found.
Levenberg-Marquardt Solver (Sparse matrices version).
std::unique_ptr< LevenbergMarquardtSparse > UPtr
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...
double _weight_adapt_factor_eq
Generic interface for optimization problem definitions.
void clear() override
Clear internal caches.
double _weight_adapt_factor_ineq
void adaptWeights()
Perform single weight adapation step.
double _weight_adapt_max_ineq
void computeValues(OptimizationProblemInterface &problem)
Compute overall value vector including constraint approximation.
std::shared_ptr< NlpSolverInterface > Ptr
bool isLsqSolver() const override
Return true if the solver onyl supports costs in lsq form.
Generic interface for solver implementations.
A direct sparse LLT Cholesky factorizations.
Eigen::SparseMatrix< double > _jacobian
double _weight_adapt_factor_bounds
SolverStatus solve(OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override
Solve the provided optimization problem.
std::shared_ptr< LevenbergMarquardtSparse > Ptr
#define FACTORY_REGISTER_NLP_SOLVER(type)
double _weight_adapt_max_eq
void setPenaltyWeights(double weight_eq, double weight_ineq, double weight_bounds)
Define penalty weights (equality constraints, inequality constraints, bounds)
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.