提交 3b715f56 编写于 作者: J JasonZhou404 提交者: Jiangtao Hu

Planning: OpenSpace: ADOL-C installed

上级 2bcfc2e7
......@@ -25,7 +25,7 @@ wget https://www.coin-or.org/download/source/ADOL-C/ADOL-C-2.6.3.zip -O ADOL-C-2
unzip ADOL-C-2.6.3.zip
pushd ADOL-C-2.6.3
./configure --prefix="/apollo/docker/build/installers/ADOL-C-2.6.3" --enable-sparse ADD_CXXFLAGS="-fPIC" ADD_CFLAGS="-fPIC" ADD_FFLAGS="-fPIC"
./configure --prefix="/apollo/docker/build/installers/ADOL-C-2.6.3" ADD_CXXFLAGS="-fPIC" ADD_CFLAGS="-fPIC" ADD_FFLAGS="-fPIC"
make -j8 all
make install
......@@ -33,5 +33,7 @@ mkdir -p /usr/local/adolc
cp -r include /usr/local/adolc/ && cp -r lib64 /usr/local/adolc/
popd
export LD_LIBRARY_PATH=/usr/local/adolc/lib64
# Clean up.
rm -fr ADOL-C-2.6.3.zip ADOL-C-2.6.3
/*----------------------------------------------------------------------------
ADOL-C -- Automatic Differentiation by Overloading in C++
File: ADOL-C_sparseNLP.cpp
File: ADOL-C_NLP.cpp
Revision: $$
Contents: class myADOLC_sparseNPL for interfacing with Ipopt
Contents: class myADOLC_NPL for interfacing with Ipopt
Copyright (c) Andrea Walther
This file is part of ADOL-C. This software is provided as open source.
Any use, reproduction, or distribution of the software constitutes
Any use, reproduction, or distribution of the software constitutes
recipient's acceptance of the terms of the accompanying license file.
This code is based on the file MyNLP.cpp contained in the Ipopt package
with the authors: Carl Laird, Andreas Waechter
with the authors: Carl Laird, Andreas Waechter
----------------------------------------------------------------------------*/
/** C++ Example NLP for interfacing a problem with IPOPT and ADOL-C.
* MyADOLC_sparseNLP implements a C++ example showing how to interface
* with IPOPT and ADOL-C through the TNLP interface. This class
* MyADOL-C_NLP implements a C++ example showing how to interface
* with IPOPT and ADOL-C through the TNLP interface. This class
* implements the Example 5.1 from "Sparse and Parially Separable
* Test Problems for Unconstrained and Equality Constrained
* Optimization" by L. Luksan and J. Vlcek taking sparsity
* into account.
* Optimization" by L. Luksan and J. Vlcek ignoring sparsity.
*
* exploitation of sparsity !!
* no exploitation of sparsity !!
*
*/
#include <cassert>
#include "ADOL-C_sparseNLP.hpp"
#include "ADOL-C_NLP.hpp"
using namespace Ipopt;
/* Constructor. */
MyADOLC_sparseNLP::MyADOLC_sparseNLP()
{}
MyADOLC_NLP::MyADOLC_NLP() {}
MyADOLC_NLP::~MyADOLC_NLP() {}
bool MyADOLC_NLP::get_nlp_info(Index& n, Index& m, Index& nnz_jac_g,
Index& nnz_h_lag, IndexStyleEnum& index_style) {
n = 20;
MyADOLC_sparseNLP::~MyADOLC_sparseNLP()
{}
m = n - 2;
bool MyADOLC_sparseNLP::get_nlp_info(Index& n, Index& m, Index& nnz_jac_g,
Index& nnz_h_lag, IndexStyleEnum& index_style)
{
n = 4000;
// in this example the jacobian is dense. Hence, it contains n*m nonzeros
nnz_jac_g = n * m;
m = n-2;
// the hessian is also dense and has n*n total nonzeros, but we
// only need the lower left corner (since it is symmetric)
nnz_h_lag = n * (n - 1) / 2 + n;
generate_tapes(n, m, nnz_jac_g, nnz_h_lag);
generate_tapes(n, m);
// use the C style indexing (0-based)
index_style = C_STYLE;
......@@ -54,17 +56,16 @@ bool MyADOLC_sparseNLP::get_nlp_info(Index& n, Index& m, Index& nnz_jac_g,
return true;
}
bool MyADOLC_sparseNLP::get_bounds_info(Index n, Number* x_l, Number* x_u,
Index m, Number* g_l, Number* g_u)
{
bool MyADOLC_NLP::get_bounds_info(Index n, Number* x_l, Number* x_u, Index m,
Number* g_l, Number* g_u) {
// none of the variables have bounds
for (Index i=0; i<n; i++) {
for (Index i = 0; i < n; i++) {
x_l[i] = -1e20;
x_u[i] = 1e20;
x_u[i] = 1e20;
}
// Set the bounds for the constraints
for (Index i=0; i<m; i++) {
for (Index i = 0; i < m; i++) {
g_l[i] = 0;
g_u[i] = 0;
}
......@@ -72,11 +73,10 @@ bool MyADOLC_sparseNLP::get_bounds_info(Index n, Number* x_l, Number* x_u,
return true;
}
bool MyADOLC_sparseNLP::get_starting_point(Index n, bool init_x, Number* x,
bool init_z, Number* z_L, Number* z_U,
Index m, bool init_lambda,
Number* lambda)
{
bool MyADOLC_NLP::get_starting_point(Index n, bool init_x, Number* x,
bool init_z, Number* z_L, Number* z_U,
Index m, bool init_lambda,
Number* lambda) {
// Here, we assume we only have starting values for x, if you code
// your own NLP, you can provide starting values for the others if
// you wish.
......@@ -85,36 +85,36 @@ bool MyADOLC_sparseNLP::get_starting_point(Index n, bool init_x, Number* x,
assert(init_lambda == false);
// set the starting point
for (Index i=0; i<n/2; i++) {
x[2*i] = -1.2;
x[2*i+1] = 1.;
for (Index i = 0; i < n / 2; i++) {
x[2 * i] = -1.2;
x[2 * i + 1] = 1.;
}
if (n != 2*(n/2)) {
x[n-1] = -1.2;
if (n != 2 * (n / 2)) {
x[n - 1] = -1.2;
}
return true;
}
template<class T> bool MyADOLC_sparseNLP::eval_obj(Index n, const T *x, T& obj_value)
{
template <class T>
bool MyADOLC_NLP::eval_obj(Index n, const T* x, T& obj_value) {
T a1, a2;
obj_value = 0.;
for (Index i=0; i<n-1; i++) {
a1 = x[i]*x[i]-x[i+1];
for (Index i = 0; i < n - 1; i++) {
a1 = x[i] * x[i] - x[i + 1];
a2 = x[i] - 1.;
obj_value += 100.*a1*a1 + a2*a2;
obj_value += 100. * a1 * a1 + a2 * a2;
}
return true;
}
template<class T> bool MyADOLC_sparseNLP::eval_constraints(Index n, const T *x, Index m, T* g)
{
for (Index i=0; i<m; i++) {
g[i] = 3.*pow(x[i+1],3.) + 2.*x[i+2] - 5.
+ sin(x[i+1]-x[i+2])*sin(x[i+1]+x[i+2]) + 4.*x[i+1]
- x[i]*exp(x[i]-x[i+1]) - 3.;
template <class T>
bool MyADOLC_NLP::eval_constraints(Index n, const T* x, Index m, T* g) {
for (Index i = 0; i < m; i++) {
g[i] = 3. * pow(x[i + 1], 3.) + 2. * x[i + 2] - 5. +
sin(x[i + 1] - x[i + 2]) * sin(x[i + 1] + x[i + 2]) + 4. * x[i + 1] -
x[i] * exp(x[i] - x[i + 1]) - 3.;
}
return true;
......@@ -128,212 +128,182 @@ template<class T> bool MyADOLC_sparseNLP::eval_constraints(Index n, const T *x,
//
//*************************************************************************
bool MyADOLC_sparseNLP::eval_f(Index n, const Number* x, bool new_x, Number& obj_value)
{
eval_obj(n,x,obj_value);
bool MyADOLC_NLP::eval_f(Index n, const Number* x, bool new_x,
Number& obj_value) {
eval_obj(n, x, obj_value);
return true;
}
bool MyADOLC_sparseNLP::eval_grad_f(Index n, const Number* x, bool new_x, Number* grad_f)
{
gradient(tag_f,n,x,grad_f);
bool MyADOLC_NLP::eval_grad_f(Index n, const Number* x, bool new_x,
Number* grad_f) {
gradient(tag_f, n, x, grad_f);
return true;
}
bool MyADOLC_sparseNLP::eval_g(Index n, const Number* x, bool new_x, Index m, Number* g)
{
eval_constraints(n,x,m,g);
bool MyADOLC_NLP::eval_g(Index n, const Number* x, bool new_x, Index m,
Number* g) {
eval_constraints(n, x, m, g);
return true;
}
bool MyADOLC_sparseNLP::eval_jac_g(Index n, const Number* x, bool new_x,
Index m, Index nele_jac, Index* iRow, Index *jCol,
Number* values)
{
bool MyADOLC_NLP::eval_jac_g(Index n, const Number* x, bool new_x, Index m,
Index nele_jac, Index* iRow, Index* jCol,
Number* values) {
if (values == NULL) {
// return the structure of the jacobian
for(Index idx=0; idx<nnz_jac; idx++)
{
iRow[idx] = rind_g[idx];
jCol[idx] = cind_g[idx];
// return the structure of the jacobian,
// assuming that the Jacobian is dense
Index idx = 0;
for (Index i = 0; i < m; i++)
for (Index j = 0; j < n; j++) {
iRow[idx] = i;
jCol[idx++] = j;
}
}
else {
} else {
// return the values of the jacobian of the constraints
sparse_jac(tag_g, m, n, 1, x, &nnz_jac, &rind_g, &cind_g, &jacval, options_g);
for(Index idx=0; idx<nnz_jac; idx++)
{
values[idx] = jacval[idx];
jacobian(tag_g, m, n, x, Jac);
}
Index idx = 0;
for (Index i = 0; i < m; i++)
for (Index j = 0; j < n; j++) values[idx++] = Jac[i][j];
}
return true;
}
bool MyADOLC_sparseNLP::eval_h(Index n, const Number* x, bool new_x,
Number obj_factor, Index m, const Number* lambda,
bool new_lambda, Index nele_hess, Index* iRow,
Index* jCol, Number* values)
{
bool MyADOLC_NLP::eval_h(Index n, const Number* x, bool new_x,
Number obj_factor, Index m, const Number* lambda,
bool new_lambda, Index nele_hess, Index* iRow,
Index* jCol, Number* values) {
if (values == NULL) {
// return the structure. This is a symmetric matrix, fill the lower left
// triangle only.
for(Index idx=0; idx<nnz_L; idx++)
{
iRow[idx] = rind_L[idx];
jCol[idx] = cind_L[idx];
// the hessian for this problem is actually dense
Index idx = 0;
for (Index row = 0; row < n; row++) {
for (Index col = 0; col <= row; col++) {
iRow[idx] = row;
jCol[idx] = col;
idx++;
}
}
else {
}
assert(idx == nele_hess);
} else {
// return the values. This is a symmetric matrix, fill the lower left
// triangle only
obj_lam[0] = obj_factor;
for(Index idx = 0; idx<m ; idx++)
obj_lam[1+idx] = lambda[idx];
set_param_vec(tag_L,m+1,obj_lam);
sparse_hess(tag_L, n, 1, const_cast<double*>(x), &nnz_L, &rind_L, &cind_L, &hessval, options_L);
for(Index idx = 0; idx <nnz_L ; idx++)
{
values[idx] = hessval[idx];
for (Index i = 0; i < m; i++) obj_lam[1 + i] = lambda[i];
set_param_vec(tag_L, m + 1, obj_lam);
hessian(tag_L, n, const_cast<double*>(x), Hess);
Index idx = 0;
for (Index i = 0; i < n; i++) {
for (Index j = 0; j <= i; j++) {
values[idx++] = Hess[i][j];
}
}
}
return true;
}
void MyADOLC_sparseNLP::finalize_solution(SolverReturn status,
Index n, const Number* x, const Number* z_L, const Number* z_U,
Index m, const Number* g, const Number* lambda,
Number obj_value,
const IpoptData* ip_data,
IpoptCalculatedQuantities* ip_cq)
{
void MyADOLC_NLP::finalize_solution(SolverReturn status, Index n,
const Number* x, const Number* z_L,
const Number* z_U, Index m, const Number* g,
const Number* lambda, Number obj_value,
const IpoptData* ip_data,
IpoptCalculatedQuantities* ip_cq) {
printf("\n\nObjective value\n");
printf("f(x*) = %e\n", obj_value);
// memory deallocation of ADOL-C variables
// Memory deallocation for ADOL-C variables
delete[] obj_lam;
free(rind_g);
free(cind_g);
free(rind_L);
free(cind_L);
free(jacval);
free(hessval);
}
for (Index i = 0; i < m; i++) delete[] Jac[i];
delete[] Jac;
for (Index i = 0; i < n; i++) delete[] Hess[i];
delete[] Hess;
}
//*************** ADOL-C part ***********************************
void MyADOLC_sparseNLP::generate_tapes(Index n, Index m, Index& nnz_jac_g, Index& nnz_h_lag)
{
Number *xp = new double[n];
Number *lamp = new double[m];
Number *zl = new double[m];
Number *zu = new double[m];
void MyADOLC_NLP::generate_tapes(Index n, Index m) {
Number* xp = new double[n];
Number* lamp = new double[m];
Number* zl = new double[m];
Number* zu = new double[m];
adouble *xa = new adouble[n];
adouble *g = new adouble[m];
double *lam = new double[m];
adouble* xa = new adouble[n];
adouble* g = new adouble[m];
double* lam = new double[m];
double sig;
adouble obj_value;
double dummy;
//int i,j,k,l,ii;
Jac = new double*[m];
for (Index i = 0; i < m; i++) Jac[i] = new double[n];
obj_lam = new double[m + 1];
obj_lam = new double[m+1];
Hess = new double*[n];
for (Index i = 0; i < n; i++) Hess[i] = new double[i + 1];
get_starting_point(n, 1, xp, 0, zl, zu, m, 0, lamp);
trace_on(tag_f);
for(Index idx=0;idx<n;idx++)
xa[idx] <<= xp[idx];
eval_obj(n,xa,obj_value);
for (Index i = 0; i < n; i++) xa[i] <<= xp[i];
obj_value >>= dummy;
eval_obj(n, xa, obj_value);
obj_value >>= dummy;
trace_off();
trace_on(tag_g);
for(Index idx=0;idx<n;idx++)
xa[idx] <<= xp[idx];
eval_constraints(n,xa,m,g);
for (Index i = 0; i < n; i++) xa[i] <<= xp[i];
eval_constraints(n, xa, m, g);
for(Index idx=0;idx<m;idx++)
g[idx] >>= dummy;
for (Index i = 0; i < m; i++) g[i] >>= dummy;
trace_off();
trace_on(tag_L);
for(Index idx=0;idx<n;idx++)
xa[idx] <<= xp[idx];
for(Index idx=0;idx<m;idx++)
lam[idx] = 1.0;
sig = 1.0;
eval_obj(n,xa,obj_value);
obj_value *= mkparam(sig);
eval_constraints(n,xa,m,g);
for(Index idx=0;idx<m;idx++)
obj_value += g[idx]*mkparam(lam[idx]);
obj_value >>= dummy;
trace_off();
for (Index i = 0; i < n; i++) xa[i] <<= xp[i];
for (Index i = 0; i < m; i++) lam[i] = 1.0;
sig = 1.0;
rind_g = NULL;
cind_g = NULL;
rind_L = NULL;
cind_L = NULL;
eval_obj(n, xa, obj_value);
options_g[0] = 0; /* sparsity pattern by index domains (default) */
options_g[1] = 0; /* safe mode (default) */
options_g[2] = 0;
options_g[3] = 0; /* column compression (default) */
jacval=NULL;
hessval=NULL;
sparse_jac(tag_g, m, n, 0, xp, &nnz_jac, &rind_g, &cind_g, &jacval, options_g);
obj_value *= mkparam(sig);
eval_constraints(n, xa, m, g);
nnz_jac_g = nnz_jac;
for (Index i = 0; i < m; i++) obj_value += g[i] * mkparam(lam[i]);
options_L[0] = 0;
options_L[1] = 1;
obj_value >>= dummy;
sparse_hess(tag_L, n, 0, xp, &nnz_L, &rind_L, &cind_L, &hessval, options_L);
nnz_h_lag = nnz_L;
trace_off();
delete[] lam;
delete[] g;
delete[] xa;
delete[] xp;
delete[] g;
delete[] lam;
delete[] lamp;
delete[] zu;
delete[] zl;
delete[] lamp;
delete[] xp;
}
/*----------------------------------------------------------------------------
ADOL-C -- Automatic Differentiation by Overloading in C++
File: ADOL-C_sparseNLP.hpp
File: ADOL-C_NLP.hpp
Revision: $$
Contents: class myADOL-C_sparseNPL for interfacing with Ipopt
Contents: class myADOL-C_NPL for interfacing with Ipopt
Copyright (c) Andrea Walther
This file is part of ADOL-C. This software is provided as open source.
Any use, reproduction, or distribution of the software constitutes
Any use, reproduction, or distribution of the software constitutes
recipient's acceptance of the terms of the accompanying license file.
This code is based on the file MyNLP.hpp contained in the Ipopt package
with the authors: Carl Laird, Andreas Waechter
with the authors: Carl Laird, Andreas Waechter
----------------------------------------------------------------------------*/
//*************************************************************************
......@@ -25,25 +25,22 @@
#ifndef __MYADOLCNLP_HPP__
#define __MYADOLCNLP_HPP__
#include <IpTNLP.hpp>
#include <adolc/adolc.h>
#include <adolc/adolc_sparse.h>
#include "IpTNLP.hpp"
#include "adolc/adolc.h"
#define tag_f 1
#define tag_g 2
#define tag_L 3
#define HPOFF 30
using namespace Ipopt;
class MyADOLC_sparseNLP : public TNLP
{
public:
class MyADOLC_NLP : public TNLP {
public:
/** default constructor */
MyADOLC_sparseNLP();
MyADOLC_NLP();
/** default destructor */
virtual ~MyADOLC_sparseNLP();
virtual ~MyADOLC_NLP();
/**@name Overloaded from TNLP */
//@{
......@@ -52,21 +49,21 @@ public:
Index& nnz_h_lag, IndexStyleEnum& index_style);
/** Method to return the bounds for my problem */
virtual bool get_bounds_info(Index n, Number* x_l, Number* x_u,
Index m, Number* g_l, Number* g_u);
virtual bool get_bounds_info(Index n, Number* x_l, Number* x_u, Index m,
Number* g_l, Number* g_u);
/** Method to return the starting point for the algorithm */
virtual bool get_starting_point(Index n, bool init_x, Number* x,
bool init_z, Number* z_L, Number* z_U,
Index m, bool init_lambda,
Number* lambda);
virtual bool get_starting_point(Index n, bool init_x, Number* x, bool init_z,
Number* z_L, Number* z_U, Index m,
bool init_lambda, Number* lambda);
/** Template to return the objective value */
template<class T> bool eval_obj(Index n, const T *x, T& obj_value);
template <class T>
bool eval_obj(Index n, const T* x, T& obj_value);
/** Template to compute contraints */
template<class T> bool eval_constraints(Index n, const T *x, Index m, T *g);
template <class T>
bool eval_constraints(Index n, const T* x, Index m, T* g);
/** Original method from Ipopt to return the objective value */
/** remains unchanged */
......@@ -74,7 +71,8 @@ public:
/** Original method from Ipopt to return the gradient of the objective */
/** remains unchanged */
virtual bool eval_grad_f(Index n, const Number* x, bool new_x, Number* grad_f);
virtual bool eval_grad_f(Index n, const Number* x, bool new_x,
Number* grad_f);
/** Original method from Ipopt to return the constraint residuals */
/** remains unchanged */
......@@ -85,8 +83,8 @@ public:
* 2) The values of the jacobian (if "values" is not NULL)
*/
/** remains unchanged */
virtual bool eval_jac_g(Index n, const Number* x, bool new_x,
Index m, Index nele_jac, Index* iRow, Index *jCol,
virtual bool eval_jac_g(Index n, const Number* x, bool new_x, Index m,
Index nele_jac, Index* iRow, Index* jCol,
Number* values);
/** Original method from Ipopt to return:
......@@ -94,66 +92,54 @@ public:
* 2) The values of the hessian of the lagrangian (if "values" is not NULL)
*/
/** remains unchanged */
virtual bool eval_h(Index n, const Number* x, bool new_x,
Number obj_factor, Index m, const Number* lambda,
bool new_lambda, Index nele_hess, Index* iRow,
Index* jCol, Number* values);
virtual bool eval_h(Index n, const Number* x, bool new_x, Number obj_factor,
Index m, const Number* lambda, bool new_lambda,
Index nele_hess, Index* iRow, Index* jCol,
Number* values);
//@}
/** @name Solution Methods */
//@{
/** This method is called when the algorithm is complete so the TNLP can store/write the solution */
virtual void finalize_solution(SolverReturn status,
Index n, const Number* x, const Number* z_L, const Number* z_U,
Index m, const Number* g, const Number* lambda,
Number obj_value,
const IpoptData* ip_data,
IpoptCalculatedQuantities* ip_cq);
/** This method is called when the algorithm is complete so the TNLP can
* store/write the solution */
virtual void finalize_solution(SolverReturn status, Index n, const Number* x,
const Number* z_L, const Number* z_U, Index m,
const Number* g, const Number* lambda,
Number obj_value, const IpoptData* ip_data,
IpoptCalculatedQuantities* ip_cq);
//@}
//*************** start ADOL-C part ***********************************
//*************** start ADOL-C part ***********************************
/** Method to generate the required tapes */
virtual void generate_tapes(Index n, Index m, Index& nnz_jac_g, Index& nnz_h_lag);
/** Method to generate the required tapes */
virtual void generate_tapes(Index n, Index m);
//*************** end ADOL-C part ***********************************
//*************** end ADOL-C part ***********************************
private:
private:
/**@name Methods to block default compiler methods.
* The compiler automatically generates the following three methods.
* Since the default compiler implementation is generally not what
* you want (for all but the most simple classes), we usually
* you want (for all but the most simple classes), we usually
* put the declarations of these methods in the private section
* and never implement them. This prevents the compiler from
* implementing an incorrect "default" behavior without us
* knowing. (See Scott Meyers book, "Effective C++")
*
*
*/
//@{
// MyADOLC_sparseNLP();
MyADOLC_sparseNLP(const MyADOLC_sparseNLP&);
MyADOLC_sparseNLP& operator=(const MyADOLC_sparseNLP&);
// MyADOLC_NLP();
MyADOLC_NLP(const MyADOLC_NLP&);
MyADOLC_NLP& operator=(const MyADOLC_NLP&);
//@}
//@{
double** Jac;
double *obj_lam;
//** variables for sparsity exploitation
unsigned int *rind_g; /* row indices */
unsigned int *cind_g; /* column indices */
double *jacval; /* values */
unsigned int *rind_L; /* row indices */
unsigned int *cind_L; /* column indices */
double *hessval; /* values */
int nnz_jac;
int nnz_L;
int options_g[4];
int options_L[4];
double* obj_lam;
double** Hess;
//@}
};
#endif
......@@ -315,13 +315,16 @@ cc_binary(
name = "ADOL-C_exmples",
srcs = [
"cpp_example.cpp",
"ADOL-C_sparseNLP.cpp",
"ADOL-C_sparseNLP.hpp",
"ADOL-C_NLP.cpp",
"ADOL-C_NLP.hpp",
],
deps = [
"@adolc",
"@ipopt",
],
linkopts = [
"-L/usr/local/adolc/lib64 -ladolc",
],
)
cpplint()
......@@ -2,16 +2,16 @@
ADOL-C -- Automatic Differentiation by Overloading in C++
File: cpp_example.cpp
Revision: $$
Contents: example for class myADOLC_sparseNPL for interfacing with Ipopt
Contents: example for class myADOLC_NPL for interfacing with Ipopt
Copyright (c) Andrea Walther
This file is part of ADOL-C. This software is provided as open source.
Any use, reproduction, or distribution of the software constitutes
Any use, reproduction, or distribution of the software constitutes
recipient's acceptance of the terms of the accompanying license file.
This code is based on the file corresponding file cpp_example.cpp contained
in the Ipopt package with the authors: Carl Laird, Andreas Waechter
This code is based on the file corresponding file cpp_example.cpp contained
in the Ipopt package with the authors: Carl Laird, Andreas Waechter
----------------------------------------------------------------------------*/
//*************************************************************************
......@@ -22,16 +22,15 @@
//
//*************************************************************************
#include "ADOL-C_NLP.hpp"
#include "IpIpoptApplication.hpp"
#include "IpSolveStatistics.hpp"
#include "ADOL-C_sparseNLP.hpp"
using namespace Ipopt;
int main(int argv, char* argc[])
{
int main(int argv, char* argc[]) {
// Create an instance of your nlp...
SmartPtr<TNLP> myadolc_nlp = new MyADOLC_sparseNLP();
SmartPtr<TNLP> myadolc_nlp = new MyADOLC_NLP();
// Create an instance of the IpoptApplication
SmartPtr<IpoptApplication> app = new IpoptApplication();
......@@ -41,7 +40,7 @@ int main(int argv, char* argc[])
status = app->Initialize();
if (status != Solve_Succeeded) {
printf("\n\n*** Error during initialization!\n");
return (int) status;
return (int)status;
}
status = app->OptimizeTNLP(myadolc_nlp);
......@@ -52,8 +51,9 @@ int main(int argv, char* argc[])
printf("\n\n*** The problem solved in %d iterations!\n", iter_count);
Number final_obj = app->Statistics()->FinalObjective();
printf("\n\n*** The final value of the objective function is %e.\n", final_obj);
printf("\n\n*** The final value of the objective function is %e.\n",
final_obj);
}
return (int) status;
return (int)status;
}
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册