52   Flow   = 
new double[neF];
    53   Fupp   = 
new double[neF];
    54   Fmul   = 
new double[neF];
    55   Fstate = 
new    int[neF];
    60   for (uint _n=0; _n<bounds_x.size(); ++_n) {
    61     xlow[_n] = bounds_x.at(_n).lower_;
    62     xupp[_n] = bounds_x.at(_n).upper_;
    69     Flow[c] = -1e20; Fupp[c] = 1e20; Fmul[c] = 0.0; 
    75   for (
const auto& b : bounds_g) {
    76     Flow[c] = b.lower_; Fupp[c] = b.upper_; Fmul[c] = 0.0;
    82   Eigen::Map<VectorXd>(&x[0], x_all.rows()) = x_all;
    96   iGfun = 
new int[lenG];
    97   jGvar = 
new int[lenG];
   104     for (
int var=0; var<n; ++var) {
   113   for (
int k=0; k<jac.outerSize(); ++k) {
   114     for (Jacobian::InnerIterator it(jac,k); it; ++it) {
   115       iGfun[neG] = it.row() + obj_count;
   116       jGvar[neG] = it.col();
   126                                          int* needF, 
int* neF, 
double F[],
   127                                          int* needG, 
int* neG, 
double G[],
   128                                          char* cu, 
int* lencu, 
int iu[],
   129                                          int* leniu, 
double ru[], 
int* lenru)
   140     Eigen::Map<VectorXd>(F+i, g_eig.rows()) = g_eig;
   151       Eigen::Map<VectorXd>(G, i) = grad;
 Problem::VectorXd VectorXd
A generic optimization problem with variables, costs and constraints. 
VecBound GetBoundsOnConstraints() const 
The upper and lower bound of each individual constraint. 
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)
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x. 
VectorXd GetVariableValues() const 
The current value of the optimization variables. 
VectorXd EvaluateCostFunctionGradient(const double *x)
The column-vector of derivatives of the cost w.r.t. each variable. 
void SaveCurrent()
Saves the current values of the optimization variables in x_prev. 
bool HasCostTerms() const 
True if the optimization problem includes a cost, false if merely a feasibility problem is defined...
VecBound GetBoundsOnOptimizationVariables() const 
The maximum and minimum value each optimization variable is allowed to have. 
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. 
common namespace for all elements in this library. 
SnoptAdapter(Problem &nlp)
Creates an Adapter Object around the problem to conform to the Snopt interface. 
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. 
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x. 
int GetNumberOfOptimizationVariables() const 
The number of optimization variables.