Go to the documentation of this file.
   25 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_DENSE_H_ 
   26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_DENSE_H_ 
   62 class LevenbergMarquardtDense : 
public NlpSolverInterface
 
   65     using Ptr  = std::shared_ptr<LevenbergMarquardtDense>;
 
   66     using UPtr = std::unique_ptr<LevenbergMarquardtDense>;
 
   75     bool initialize(OptimizationProblemInterface* problem = 
nullptr) 
override;
 
   77     SolverStatus solve(OptimizationProblemInterface& problem, 
bool new_structure = 
true, 
bool new_run = 
true, 
double* obj_value = 
nullptr) 
override;
 
   82     void setPenaltyWeights(
double weight_eq, 
double weight_ineq, 
double weight_bounds);
 
   84     void setWeightAdapation(
double factor_eq, 
double factor_ineq, 
double factor_bounds, 
double max_eq, 
double max_ineq, 
double max_bounds);
 
   87     void clear() 
override;
 
   89 #ifdef MESSAGE_SUPPORT 
   91     void toMessage(corbo::messages::NlpSolver& message) 
const override;
 
   93     void fromMessage(
const corbo::messages::NlpSolver& message, std::stringstream* issues = 
nullptr) 
override;
 
  135     Eigen::VectorXd 
_rhs;
 
  146 #endif  // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_LEVENBERG_MARQUARDT_DENSE_H_ 
  
double _weight_init_bounds
NlpSolverInterface::Ptr getInstance() const override
Return a newly created instance of the current solver.
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.
void computeJacobian(OptimizationProblemInterface &problem)
Compute overall jacobian including constraint approximation.
double _weight_adapt_max_eq
std::shared_ptr< NlpSolverInterface > Ptr
bool isLsqSolver() const override
Return true if the solver onyl supports costs in lsq form.
void setPenaltyWeights(double weight_eq, double weight_ineq, double weight_bounds)
Define penalty weights (equality constraints, inequality constraints, bounds)
void adaptWeights()
Perform single weight adapation step.
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...
void clear() override
Clear internal caches.
double _weight_adapt_max_bounds
std::unique_ptr< LevenbergMarquardtDense > UPtr
void computeValues(OptimizationProblemInterface &problem)
Compute overall value vector including constraint approximation.
double _weight_adapt_max_ineq
double _weight_adapt_factor_ineq
double _weight_adapt_factor_bounds
#define FACTORY_REGISTER_NLP_SOLVER(type)
Eigen::MatrixXd _jacobian
SolverStatus solve(OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override
Solve the provided optimization problem.
Levenberg-Marquardt Solver (Dense matrices version).
double _weight_adapt_factor_eq
Generic interface for optimization problem definitions.
void setIterations(int iterations)
Define the number of solver iterations.
std::shared_ptr< LevenbergMarquardtDense > Ptr
void resetWeights()
Reset weights to their original values.
control_box_rst
Author(s): Christoph Rösmann 
autogenerated on Wed Mar 2 2022 00:05:52