Go to the documentation of this file.
30 #ifndef IFOPT_INCLUDE_OPT_PROBLEM_H_
31 #define IFOPT_INCLUDE_OPT_PROBLEM_H_
177 const double* x,
bool use_finite_difference_approximation =
false,
178 double epsilon = std::numeric_limits<double>::epsilon());
273 std::vector<VectorXd>
x_prev;
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.
const std::vector< VectorXd > & GetIterations() const
Read access to the history of iterations.
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.
Component::VecBound VecBound
std::vector< Bounds > 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.
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
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.
virtual ~Problem()=default
A collection of components which is treated as another Component.
const Composite & GetConstraints() const
Read access to the constraints composite.
std::shared_ptr< ConstraintSet > Ptr
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
Composite::Ptr GetOptVariables() const
Read/write access to the current optimization variables.
void PrintCurrent() const
Prints the variables, costs and constraints.
const Composite & GetCosts() const
Read access to the costs composite.
VectorXd ConvertToEigen(const double *x) const
ifopt
Author(s): Alexander W. Winkler
autogenerated on Mon Sep 18 2023 02:14:38