Go to the documentation of this file.
51 Flow =
new double[neF];
52 Fupp =
new double[neF];
53 Fmul =
new double[neF];
54 Fstate =
new int[neF];
59 for (std::size_t _n = 0; _n < bounds_x.size(); ++_n) {
60 xlow[_n] = bounds_x.at(_n).lower_;
61 xupp[_n] = bounds_x.at(_n).upper_;
76 for (
const auto& b : bounds_g) {
85 Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
102 iGfun =
new int[lenG];
103 jGvar =
new int[lenG];
110 for (
int var = 0; var < n; ++var) {
119 for (
int k = 0; k < jac.outerSize(); ++k) {
120 for (Jacobian::InnerIterator it(jac, k); it; ++it) {
121 iGfun[neG] = it.row() + obj_count;
122 jGvar[neG] = it.col();
131 int* needF,
int* neF,
double F[],
132 int* needG,
int* neG,
double G[],
133 char* cu,
int* lencu,
int iu[],
134 int* leniu,
double ru[],
146 Eigen::Map<VectorXd>(F + i, g_eig.rows()) = g_eig;
156 Eigen::Map<VectorXd>(G, i) = grad;
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.
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
Problem::VectorXd VectorXd
bool HasCostTerms() const
True if the optimization problem includes a cost, false if merely a feasibility problem is defined.
void EvalNonzerosOfJacobian(const double *x, double *values)
Extracts those entries from constraint Jacobian that are not zero.
int GetNumberOfConstraints() const
The number of individual constraints.
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
static void ObjectiveAndConstraintFct(int *Status, int *n, double x[], int *needF, int *neF, double F[], int *needG, int *neG, double G[], char *cu, int *lencu, int iu[], int *leniu, double ru[], int *lenru)
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
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.
common namespace for all elements in this library.
void SaveCurrent()
Saves the current values of the optimization variables in x_prev.
SnoptAdapter(Problem &nlp)
Creates an Adapter Object around the problem to conform to the Snopt interface.
ifopt
Author(s): Alexander W. Winkler
autogenerated on Mon Sep 18 2023 02:14:38