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 
68 class LevenbergMarquardtSparse : public NlpSolverInterface
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 
118  double _weight_adapt_factor_eq = 1;
120  double _weight_adapt_factor_bounds = 1;
121 
122  double _weight_adapt_max_eq = 500;
123  double _weight_adapt_max_ineq = 500;
124  double _weight_adapt_max_bounds = 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;
131  int _finite_bounds_dim = 0;
132  int _val_dim = 0;
133 
134  Eigen::VectorXd _values;
137  Eigen::VectorXd _delta;
138  Eigen::VectorXd _rhs;
139 
140  double _weight_eq = _weight_init_eq;
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_
corbo::LevenbergMarquardtSparse::_weight_adapt_factor_eq
double _weight_adapt_factor_eq
Definition: levenberg_marquardt_sparse.h:162
corbo::LevenbergMarquardtSparse
Levenberg-Marquardt Solver (Sparse matrices version).
Definition: levenberg_marquardt_sparse.h:90
corbo::LevenbergMarquardtSparse::UPtr
std::unique_ptr< LevenbergMarquardtSparse > UPtr
Definition: levenberg_marquardt_sparse.h:116
corbo::LevenbergMarquardtSparse::Ptr
std::shared_ptr< LevenbergMarquardtSparse > Ptr
Definition: levenberg_marquardt_sparse.h:115
Eigen::SparseMatrix< double >
corbo::LevenbergMarquardtSparse::computeValues
void computeValues(OptimizationProblemInterface &problem)
Compute overall value vector including constraint approximation.
Definition: levenberg_marquardt_sparse.cpp:244
corbo::LevenbergMarquardtSparse::_weight_adapt_factor_ineq
double _weight_adapt_factor_ineq
Definition: levenberg_marquardt_sparse.h:163
corbo::LevenbergMarquardtSparse::clear
void clear() override
Clear internal caches.
Definition: levenberg_marquardt_sparse.cpp:311
corbo::LevenbergMarquardtSparse::_ineq_dim
int _ineq_dim
Definition: levenberg_marquardt_sparse.h:174
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::LevenbergMarquardtSparse::resetWeights
void resetWeights()
Reset weights to their original values.
Definition: levenberg_marquardt_sparse.cpp:292
Eigen::Upper
@ Upper
Definition: Constants.h:206
corbo::LevenbergMarquardtSparse::isLsqSolver
bool isLsqSolver() const override
Return true if the solver onyl supports costs in lsq form.
Definition: levenberg_marquardt_sparse.h:122
corbo::LevenbergMarquardtSparse::_weight_eq
double _weight_eq
Definition: levenberg_marquardt_sparse.h:184
corbo::SolverStatus
SolverStatus
Definition: optimization/include/corbo-optimization/types.h:52
nlp_solver_interface.h
Eigen::SimplicialLLT
A direct sparse LLT Cholesky factorizations.
Definition: SimplicialCholesky.h:266
corbo::NlpSolverInterface::Ptr
std::shared_ptr< NlpSolverInterface > Ptr
Definition: nlp_solver_interface.h:114
corbo::LevenbergMarquardtSparse::_jacobian
Eigen::SparseMatrix< double > _jacobian
Definition: levenberg_marquardt_sparse.h:179
corbo::LevenbergMarquardtSparse::adaptWeights
void adaptWeights()
Perform single weight adapation step.
Definition: levenberg_marquardt_sparse.cpp:299
corbo::LevenbergMarquardtSparse::_param_dim
int _param_dim
Definition: levenberg_marquardt_sparse.h:171
corbo::LevenbergMarquardtSparse::_delta
Eigen::VectorXd _delta
Definition: levenberg_marquardt_sparse.h:181
corbo::LevenbergMarquardtSparse::setPenaltyWeights
void setPenaltyWeights(double weight_eq, double weight_ineq, double weight_bounds)
Define penalty weights (equality constraints, inequality constraints, bounds)
Definition: levenberg_marquardt_sparse.cpp:270
corbo::LevenbergMarquardtSparse::_rhs
Eigen::VectorXd _rhs
Definition: levenberg_marquardt_sparse.h:182
corbo::LevenbergMarquardtSparse::_weight_adapt_max_bounds
double _weight_adapt_max_bounds
Definition: levenberg_marquardt_sparse.h:168
corbo::LevenbergMarquardtSparse::setIterations
void setIterations(int iterations)
Define the number of solver iterations.
Definition: levenberg_marquardt_sparse.h:130
corbo::LevenbergMarquardtSparse::_weight_adapt_factor_bounds
double _weight_adapt_factor_bounds
Definition: levenberg_marquardt_sparse.h:164
corbo::LevenbergMarquardtSparse::_weight_adapt_max_eq
double _weight_adapt_max_eq
Definition: levenberg_marquardt_sparse.h:166
corbo::LevenbergMarquardtSparse::initialize
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.
Definition: levenberg_marquardt_sparse.cpp:55
corbo::LevenbergMarquardtSparse::_weight_adapt_max_ineq
double _weight_adapt_max_ineq
Definition: levenberg_marquardt_sparse.h:167
Eigen::CholmodSupernodalLLT
A supernodal Cholesky (LLT) factorization and solver based on Cholmod.
Definition: CholmodSupport.h:534
corbo::LevenbergMarquardtSparse::_weight_init_ineq
double _weight_init_ineq
Definition: levenberg_marquardt_sparse.h:159
corbo::LevenbergMarquardtSparse::solve
SolverStatus solve(OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override
Solve the provided optimization problem.
Definition: levenberg_marquardt_sparse.cpp:66
corbo::LevenbergMarquardtSparse::_iterations
int _iterations
Definition: levenberg_marquardt_sparse.h:156
corbo::LevenbergMarquardtSparse::setWeightAdapation
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...
Definition: levenberg_marquardt_sparse.cpp:281
corbo::LevenbergMarquardtSparse::_values
Eigen::VectorXd _values
Definition: levenberg_marquardt_sparse.h:178
corbo::LevenbergMarquardtSparse::getInstance
NlpSolverInterface::Ptr getInstance() const override
Return a newly created instance of the current solver.
Definition: levenberg_marquardt_sparse.h:119
FACTORY_REGISTER_NLP_SOLVER
#define FACTORY_REGISTER_NLP_SOLVER(type)
Definition: nlp_solver_interface.h:140
corbo::LevenbergMarquardtSparse::_obj_dim
int _obj_dim
Definition: levenberg_marquardt_sparse.h:172
corbo::LevenbergMarquardtSparse::_eq_dim
int _eq_dim
Definition: levenberg_marquardt_sparse.h:173
corbo::LevenbergMarquardtSparse::_finite_bounds_dim
int _finite_bounds_dim
Definition: levenberg_marquardt_sparse.h:175
corbo::LevenbergMarquardtSparse::_val_dim
int _val_dim
Definition: levenberg_marquardt_sparse.h:176
corbo::LevenbergMarquardtSparse::_sparse_solver
Eigen::SimplicialLLT< Eigen::SparseMatrix< double >, Eigen::Upper > _sparse_solver
Eigens sparse solver wrapper. Check http://eigen.tuxfamily.org/dox/group__TopicSparseSystems....
Definition: levenberg_marquardt_sparse.h:199
corbo::LevenbergMarquardtSparse::_weight_bounds
double _weight_bounds
Definition: levenberg_marquardt_sparse.h:186
corbo::LevenbergMarquardtSparse::_hessian
Eigen::SparseMatrix< double > _hessian
Definition: levenberg_marquardt_sparse.h:180
corbo::LevenbergMarquardtSparse::_weight_ineq
double _weight_ineq
Definition: levenberg_marquardt_sparse.h:185
corbo::LevenbergMarquardtSparse::_weight_init_eq
double _weight_init_eq
Definition: levenberg_marquardt_sparse.h:158
corbo::LevenbergMarquardtSparse::_weight_init_bounds
double _weight_init_bounds
Definition: levenberg_marquardt_sparse.h:160
corbo::OptimizationProblemInterface
Generic interface for optimization problem definitions.
Definition: optimization_problem_interface.h:92


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:52