levenberg_marquardt_sparse.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_SPARSE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_SPARSE_H_
27 
29 
30 #include <Eigen/Sparse>
31 
32 #ifdef CHOLMOD
33 #include <Eigen/CholmodSupport>
34 #endif
35 
36 #include <memory>
37 
38 namespace corbo {
39 
69 {
70  public:
71  using Ptr = std::shared_ptr<LevenbergMarquardtSparse>;
72  using UPtr = std::unique_ptr<LevenbergMarquardtSparse>;
73 
74  // implements interface method
75  NlpSolverInterface::Ptr getInstance() const override { return std::make_shared<LevenbergMarquardtSparse>(); }
76 
77  // implements interface method
78  bool isLsqSolver() const override { return true; }
79 
80  // implements interface method
81  bool initialize(OptimizationProblemInterface* problem = nullptr) override;
82  // implements interface method
83  SolverStatus solve(OptimizationProblemInterface& problem, bool new_structure = true, bool new_run = true, double* obj_value = nullptr) override;
84 
86  void setIterations(int iterations) { _iterations = iterations; }
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);
91 
92  void clear() override;
93 
94 #ifdef MESSAGE_SUPPORT
95  // implements interface method
96  void toMessage(corbo::messages::NlpSolver& message) const override;
97  // implements interface method
98  void fromMessage(const corbo::messages::NlpSolver& message, std::stringstream* issues = nullptr) override;
99 #endif
100 
101  protected:
104 
106  void resetWeights();
108  void adaptWeights();
109 
110  private:
111  // parameters
112  int _iterations = 10;
113 
114  double _weight_init_eq = 2;
115  double _weight_init_ineq = 2;
117 
121 
122  double _weight_adapt_max_eq = 500;
125 
126  // internal states
127  int _param_dim = 0;
128  int _obj_dim = 0;
129  int _eq_dim = 0;
130  int _ineq_dim = 0;
132  int _val_dim = 0;
133 
134  Eigen::VectorXd _values;
137  Eigen::VectorXd _delta;
138  Eigen::VectorXd _rhs;
139 
143 
151 #if defined(CHOLMOD) && !defined(FORCE_EIGEN_SOLVER)
153 #else
154  // Eigen::SimplicialLDLT<Eigen::SparseMatrix<double>, Eigen::Upper> _sparse_solver;
156 #endif
157 };
158 
160 
161 } // namespace corbo
162 
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.
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...
Generic interface for optimization problem definitions.
void clear() override
Clear internal caches.
void adaptWeights()
Perform single weight adapation step.
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
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)
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.


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