30 #ifndef IFOPT_INCLUDE_OPT_PROBLEM_H_ 31 #define IFOPT_INCLUDE_OPT_PROBLEM_H_ 178 bool use_finite_difference_approximation =
false,
179 double epsilon = std::numeric_limits<double>::epsilon());
std::vector< VectorXd > x_prev
the pure variables for every iteration.
Problem()
Creates a optimization problem with no variables, costs or constraints.
Composite::Ptr variables_
void SetOptVariables(int iter)
Sets the optimization variables to those at iteration iter.
Composite::Ptr GetOptVariables() const
Read/write access to the current optimization variables.
int GetNumberOfConstraints() const
The number of individual constraints.
A generic optimization problem with variables, costs and constraints.
void AddCostSet(CostTerm::Ptr cost_set)
Add a cost term to the optimization problem.
int GetIterationCount() const
The number of iterations it took to solve the problem.
std::shared_ptr< Composite > Ptr
Component::Jacobian Jacobian
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables 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.
VectorXd GetVariableValues() const
The current value of the optimization variables.
void PrintCurrent() const
Prints the variables, costs and constraints.
Component::VectorXd VectorXd
std::shared_ptr< Component > Ptr
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
int GetNumberOfOptimizationVariables() const
The number of optimization variables.
VectorXd ConvertToEigen(const double *x) const
Component::VecBound VecBound
virtual ~Problem()=default
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
std::shared_ptr< ConstraintSet > Ptr
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
const std::vector< VectorXd > & GetIterations() const
Read access to the history of iterations.
void SetOptVariablesFinal()
Sets the optimization variables to those of the final iteration.
bool HasCostTerms() const
True if the optimization problem includes a cost, false if merely a feasibility problem is defined...
common namespace for all elements in this library.
const Composite & GetCosts() const
Read access to the costs composite.
const Composite & GetConstraints() const
Read access to the constraints composite.
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.
A collection of components which is treated as another Component.
Jacobian GetJacobianOfCosts() const
The sparse-matrix representation of Jacobian of the costs.
std::vector< Bounds > VecBound
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
void AddVariableSet(VariableSet::Ptr variable_set)
Add one individual set of variables to the optimization problem.
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.