Go to the documentation of this file.
37 : constraints_(
"constraint-sets", false), costs_(
"cost-terms", true)
39 variables_ = std::make_shared<Composite>(
"variable-sets",
false);
90 const double* x,
bool use_finite_difference_approximation,
double epsilon)
95 if (use_finite_difference_approximation) {
96 double step_size = epsilon;
100 std::vector<double> x_new(x, x + n);
101 for (
int i = 0; i < n; ++i) {
102 x_new[i] += step_size;
104 jac.coeffRef(0, i) = (g_new - g) / step_size;
113 return jac.row(0).transpose();
142 jac.makeCompressed();
143 std::copy(jac.valuePtr(), jac.valuePtr() + jac.nonZeros(), values);
180 <<
"************************************************************\n"
181 <<
" IFOPT - Interface to Nonlinear Optimizers (v2.0)\n"
182 <<
" \u00a9 Alexander W. Winkler\n"
183 <<
" https://github.com/ethz-adrl/ifopt\n"
184 <<
"************************************************************"
187 <<
"c - number of variables, constraints or cost terms" << std::endl
188 <<
"i - indices of this set in overall problem" << std::endl
189 <<
"v - number of [violated variable- or constraint-bounds] or [cost "
192 << std::right << std::setw(33) <<
"" << std::setw(5) <<
"c "
193 << std::setw(16) <<
"i " << std::setw(11) <<
"v " << std::left
Jacobian GetJacobianOfCosts() const
The sparse-matrix representation of Jacobian of the costs.
int GetNumberOfOptimizationVariables() const
The number of optimization variables.
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x.
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
VectorXd EvaluateCostFunctionGradient(const double *x, bool use_finite_difference_approximation=false, double epsilon=std::numeric_limits< double >::epsilon())
The column-vector of derivatives of the cost w.r.t. each variable.
void AddComponent(const Component::Ptr &)
Adds a component to this composite.
Component::VecBound VecBound
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
bool HasCostTerms() const
True if the optimization problem includes a cost, false if merely a feasibility problem is defined.
Component::VectorXd VectorXd
void EvalNonzerosOfJacobian(const double *x, double *values)
Extracts those entries from constraint Jacobian that are not zero.
void AddConstraintSet(ConstraintSet::Ptr constraint_set)
Add a set of multiple constraints to the optimization problem.
std::vector< VectorXd > x_prev
the pure variables for every iteration.
VecBound GetBounds() const override
Returns the "bounds" of this component.
void SetOptVariablesFinal()
Sets the optimization variables to those of the final iteration.
Component::Jacobian Jacobian
int GetNumberOfConstraints() const
The number of individual constraints.
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
Problem()
Creates a optimization problem with no variables, costs or constraints.
void SetOptVariables(int iter)
Sets the optimization variables to those at iteration iter.
VectorXd GetVariableValues() const
The current value of the optimization variables.
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.
void AddCostSet(CostTerm::Ptr cost_set)
Add a cost term to the optimization problem.
std::shared_ptr< Composite > Ptr
Jacobian GetJacobian() const override
Returns derivatives of each row w.r.t. the variables.
int GetIterationCount() const
The number of iterations it took to solve the problem.
std::shared_ptr< Component > Ptr
void AddVariableSet(VariableSet::Ptr variable_set)
Add one individual set of variables to the optimization problem.
Composite::Ptr variables_
common namespace for all elements in this library.
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
int GetRows() const
Returns the number of rows of this component.
std::shared_ptr< ConstraintSet > Ptr
Composite::Ptr GetOptVariables() const
Read/write access to the current optimization variables.
void PrintCurrent() const
Prints the variables, costs and constraints.
VectorXd GetValues() const override
Returns the "values" of whatever this component represents.
VectorXd ConvertToEigen(const double *x) const
ifopt
Author(s): Alexander W. Winkler
autogenerated on Mon Sep 18 2023 02:14:38