42 int INFO = snopt.solve(Cold);
43 int EXIT = INFO - INFO%10;
46 std::string msg =
"Snopt failed to find a solution. EXIT:" + std::to_string(EXIT) +
", INFO:" + std::to_string(INFO);
47 throw std::runtime_error(msg);
58 solver.setProbName(
"snopt" );
59 solver.setIntParameter(
"Major Print level", 1 );
60 solver.setIntParameter(
"Minor Print level", 1 );
61 solver.setParameter(
"Solution");
62 solver.setIntParameter(
"Derivative option", 1 );
63 solver.setIntParameter(
"Verify level ", 3 );
64 solver.setIntParameter(
"Iterations limit", 200000);
65 solver.setRealParameter(
"Major feasibility tolerance", 1.0e-3);
66 solver.setRealParameter(
"Minor feasibility tolerance", 1.0e-3);
67 solver.setRealParameter(
"Major optimality tolerance", 1.0e-2);
97 for (uint _n=0; _n<bounds_x.size(); ++_n) {
98 xlow[_n] = bounds_x.at(_n).lower_;
99 xupp[_n] = bounds_x.at(_n).upper_;
112 for (
const auto& b : bounds_g) {
119 Eigen::Map<VectorXd>(&
x[0], x_all.rows()) = x_all;
141 for (
int var=0; var<
n; ++var) {
150 for (
int k=0; k<jac.outerSize(); ++k) {
151 for (Jacobian::InnerIterator it(jac,k); it; ++it) {
163 int* needF,
int*
neF,
double F[],
164 int* needG,
int*
neG,
double G[],
165 char* cu,
int* lencu,
int iu[],
166 int* leniu,
double ru[],
int* lenru)
177 Eigen::Map<VectorXd>(F+i, g_eig.rows()) = g_eig;
188 Eigen::Map<VectorXd>(G, i) = grad;
Problem::VectorXd VectorXd
VecBound GetBoundsOnConstraints() const
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)
VectorXd GetVariableValues() const
VectorXd EvaluateCostFunctionGradient(const double *x)
bool HasCostTerms() const
VecBound GetBoundsOnOptimizationVariables() const
void SetVariables(const double *x)
Jacobian GetJacobianOfConstraints() const
static void Solve(Problem &nlp)
Creates a snoptProblemA from nlp and solves it.
SnoptAdapter(Problem &nlp)
Creates an Adapter Object around the problem to conform to the Snopt interface.
void EvalNonzerosOfJacobian(const double *x, double *values)
static void SetOptions(SnoptAdapter &)
Sets solver settings for Snopt.
int GetNumberOfConstraints() const
VectorXd EvaluateConstraints(const double *x)
int GetNumberOfOptimizationVariables() const