Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Exact hess template #555

Merged
merged 45 commits into from Mar 11, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
45 commits
Select commit Hold shift + click to select a range
028ff47
templates: set option for exact hessian
FreyJo Feb 19, 2020
77dfb8e
templates: add regularization option
FreyJo Feb 19, 2020
67634e6
python: rename NLS terminal function: r -> y
FreyJo Feb 19, 2020
851f99c
python: rename NLS function: r -> y
FreyJo Feb 19, 2020
1adc33d
python: simplify casadi codegen
FreyJo Feb 19, 2020
44fcedf
python: generate all functions needed by NLS cost module
FreyJo Feb 20, 2020
8711aea
templates: set all external functions for NLS cost module
FreyJo Feb 20, 2020
eff2439
python: add Hessian approximation to test
FreyJo Feb 21, 2020
468bf45
python: add Regularizaton to test
FreyJo Feb 21, 2020
e27292f
python: test exact hessian
FreyJo Feb 21, 2020
c443a88
test_data: bump
FreyJo Feb 21, 2020
7d9aa53
Merge remote-tracking branch 'blessed/master' into exact_hess_template
FreyJo Feb 21, 2020
5e73edc
python: fix impl_dae_hess generation
FreyJo Feb 21, 2020
1c160db
templates: add impl_dae_hess
FreyJo Feb 21, 2020
59f24a3
templates: set parameter for expl_ode_hess
FreyJo Feb 21, 2020
53b2575
python: test exact hessian with IRK
FreyJo Feb 21, 2020
9f3a3a0
templates: Makefile whitespace control
FreyJo Feb 21, 2020
26e1d8f
template: fix model.h for integrator
FreyJo Feb 22, 2020
29451db
python: print test case in parse order
FreyJo Feb 22, 2020
bac504e
python test: reduce required tol by factor 10 to pass travis test
FreyJo Feb 22, 2020
ab45f82
python: test external cost with exact hessian
FreyJo Feb 23, 2020
ad984fc
python: test increase max iter 80 -> 100
FreyJo Feb 23, 2020
981453e
sqp: print_level 1 only prints residuals, n > 1 prints n-1 qp_in
FreyJo Feb 24, 2020
f2a7064
sqp: getter for statistics table
FreyJo Feb 25, 2020
75edfdc
python: getter & print routine for statistics
FreyJo Feb 25, 2020
0ff4353
python: test: initialize solver
FreyJo Feb 25, 2020
b603413
python: test: increase max_iter to 200
FreyJo Feb 25, 2020
926c912
c/python: initialize pi
FreyJo Feb 25, 2020
2a09680
gpython test: add CONVEXIFY
FreyJo Feb 25, 2020
de235df
update test_data wrt initialization
FreyJo Feb 25, 2020
c3a4049
python test: check_tol = 50 * solver_tol
FreyJo Feb 29, 2020
31313f3
matlab/octave: bump default CasADi to 3.5.1
FreyJo Feb 29, 2020
e930937
docs: update python installation instructions
FreyJo Mar 3, 2020
6fb9214
python: set plot style to not latex by default for compatibility
FreyJo Mar 4, 2020
c6354cf
blasfeo: bump for target X64_INTEL_CORE fix
FreyJo Mar 4, 2020
189603a
fix typos to wrap up #555
FreyJo Mar 9, 2020
4dd5fc3
python interface: update README reusing docs file
FreyJo Mar 9, 2020
597865b
python: test: use a fix random sample of combinations of settings/mod…
FreyJo Mar 9, 2020
286439f
Merge branch 'master' of github.com:acados/acados into exact_hess_tem…
FreyJo Mar 9, 2020
aed273e
python: getter for pi
FreyJo Mar 10, 2020
7756dc0
Merge branch 'master' of github.com:acados/acados into exact_hess_BACKUP
FreyJo Mar 10, 2020
cf1f26b
c: ocp_nlp_dims_get_from_attr fix for 'pi'
FreyJo Mar 10, 2020
1359a16
sqp_rti: regularize just before QP solve
FreyJo Mar 10, 2020
72ab3b9
sqp_rti: fix related compiler warnings, make preparation & feedback r…
FreyJo Mar 10, 2020
38fa33f
python: integrator: getter for Su
FreyJo Mar 11, 2020
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
4 changes: 2 additions & 2 deletions acados/ocp_nlp/ocp_nlp_constraints_bgh.c
Expand Up @@ -1305,8 +1305,8 @@ void ocp_nlp_constraints_bgh_bounds_update(void *config_, void *dims_, void *mod
ocp_nlp_constraints_bgh_cast_workspace(config_, dims, opts_, work_);

// extract dims
int nx = dims->nx;
int nu = dims->nu;
// int nx = dims->nx;
// int nu = dims->nu;
int nb = dims->nb;
int ng = dims->ng;
int nh = dims->nh;
Expand Down
4 changes: 2 additions & 2 deletions acados/ocp_nlp/ocp_nlp_constraints_bgp.c
Expand Up @@ -1292,8 +1292,8 @@ void ocp_nlp_constraints_bgp_bounds_update(void *config_, void *dims_, void *mod
ocp_nlp_constraints_bgp_cast_workspace(config_, dims, opts_, work_);

// extract dims
int nx = dims->nx;
int nu = dims->nu;
// int nx = dims->nx;
// int nu = dims->nu;
int nb = dims->nb;
int ng = dims->ng;
int nphi = dims->nphi;
Expand Down
21 changes: 14 additions & 7 deletions acados/ocp_nlp/ocp_nlp_sqp.c
Expand Up @@ -595,7 +595,7 @@ int ocp_nlp_sqp(void *config_, void *dims_, void *nlp_in_, void *nlp_out_,
{
printf("\n------- sqp iter %d (max_iter %d) --------\n",
sqp_iter, opts->max_iter);
if (opts->print_level > sqp_iter)
if (opts->print_level > sqp_iter + 1)
print_ocp_qp_in(nlp_mem->qp_in);
}

Expand Down Expand Up @@ -736,10 +736,10 @@ int ocp_nlp_sqp(void *config_, void *dims_, void *nlp_in_, void *nlp_out_,
omp_set_num_threads(num_threads_bkp);
#endif

if (opts->print_level > 0)
if (opts->print_level > 1)
{
printf("\n Failed to solve the following QP:\n");
if (opts->print_level > sqp_iter)
if (opts->print_level > sqp_iter + 1)
print_ocp_qp_in(nlp_mem->qp_in);
}

Expand Down Expand Up @@ -797,10 +797,6 @@ int ocp_nlp_sqp(void *config_, void *dims_, void *nlp_in_, void *nlp_out_,

if (opts->print_level > 0)
{
// print_ocp_qp_in(nlp_mem->qp_in);

printf("\n ocp_nlp_sqp: maximum iterations reached, last QP input above.\n");

printf("Residuals: stat: %e, eq: %e, ineq: %e, comp: %e.\n", mem->nlp_res->inf_norm_res_g,
mem->nlp_res->inf_norm_res_b, mem->nlp_res->inf_norm_res_d, mem->nlp_res->inf_norm_res_m );
}
Expand Down Expand Up @@ -981,6 +977,17 @@ void ocp_nlp_sqp_get(void *config_, void *dims_, void *mem_, const char *field,
double **value = return_value_;
*value = mem->stat;
}
else if (!strcmp("statistics", field))
{
int n_row = mem->stat_m<mem->sqp_iter+1 ? mem->stat_m : mem->sqp_iter+1;
double *value = return_value_;
for (int ii=0; ii<n_row; ii++)
{
value[ii+0] = ii;
for (int jj=0; jj<mem->stat_n; jj++)
value[ii+(jj+1)*n_row] = mem->stat[jj+ii*mem->stat_n];
}
}
else if (!strcmp("stat_m", field))
{
int *value = return_value_;
Expand Down
37 changes: 23 additions & 14 deletions acados/ocp_nlp/ocp_nlp_sqp_rti.c
Expand Up @@ -503,7 +503,7 @@ int ocp_nlp_sqp_rti(void *config_, void *dims_, void *nlp_in_, void *nlp_out_,

}

int ocp_nlp_sqp_rti_preparation_step(void *config_, void *dims_,
void ocp_nlp_sqp_rti_preparation_step(void *config_, void *dims_,
void *nlp_in_, void *nlp_out_, void *opts_, void *mem_, void *work_)
{
acados_timer timer1;
Expand All @@ -516,13 +516,12 @@ int ocp_nlp_sqp_rti_preparation_step(void *config_, void *dims_,
ocp_nlp_in *nlp_in = nlp_in_;
ocp_nlp_out *nlp_out = nlp_out_;
ocp_nlp_memory *nlp_mem = mem->nlp_mem;
ocp_qp_xcond_solver_config *qp_solver = config->qp_solver;
// ocp_qp_xcond_solver_config *qp_solver = config->qp_solver;

ocp_nlp_sqp_rti_workspace *work = work_;
ocp_nlp_sqp_rti_cast_workspace(config, dims, opts, mem, work);
ocp_nlp_workspace *nlp_work = work->nlp_work;

double tmp_time;
mem->time_lin = 0.0;
mem->time_reg = 0.0;

Expand Down Expand Up @@ -701,16 +700,10 @@ int ocp_nlp_sqp_rti_preparation_step(void *config_, void *dims_,
nlp_out, nlp_opts, nlp_mem, nlp_work);

mem->time_lin += acados_toc(&timer1);

// regularize Hessian
acados_tic(&timer1);
config->regularize->regularize_hessian(config->regularize,
dims->regularize, opts->nlp_opts->regularize, nlp_mem->regularize_mem);

mem->time_reg += acados_toc(&timer1);
}

int ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_,

void ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_,
void *nlp_in_, void *nlp_out_, void *opts_, void *mem_, void *work_)
{
acados_timer timer1;
Expand Down Expand Up @@ -743,11 +736,16 @@ int ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_,
ocp_nlp_approximate_qp_vectors_sqp(config, dims, nlp_in,
nlp_out, nlp_opts, nlp_mem, nlp_work);

// regularize Hessian
acados_tic(&timer1);
config->regularize->regularize_hessian(config->regularize,
dims->regularize, opts->nlp_opts->regularize, nlp_mem->regularize_mem);
mem->time_reg += acados_toc(&timer1);

if (opts->print_level > 0) {
printf("\n------- qp_in --------\n");
print_ocp_qp_in(nlp_mem->qp_in);
}
// exit(1);

if (!opts->warm_start_first_qp)
{
Expand Down Expand Up @@ -812,7 +810,7 @@ int ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_,
omp_set_num_threads(num_threads_bkp);
#endif
mem->status = ACADOS_QP_FAILURE;
return mem->status;
return;
}

ocp_nlp_update_variables_sqp(config, dims, nlp_in,
Expand All @@ -829,7 +827,7 @@ int ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_,
omp_set_num_threads(num_threads_bkp);
#endif
mem->status = ACADOS_SUCCESS;
return mem->status;

}


Expand Down Expand Up @@ -1016,6 +1014,17 @@ void ocp_nlp_sqp_rti_get(void *config_, void *dims_, void *mem_,
double **value = return_value_;
*value = mem->stat;
}
else if (!strcmp("statistics", field))
{
int n_row = 2;
double *value = return_value_;
for (int ii=0; ii<n_row; ii++)
{
value[ii+0] = ii;
for (int jj=0; jj<mem->stat_n; jj++)
value[ii+(jj+1)*n_row] = mem->stat[jj+ii*mem->stat_n];
}
}
else if (!strcmp("stat_m", field))
{
int *value = return_value_;
Expand Down
4 changes: 2 additions & 2 deletions acados/ocp_nlp/ocp_nlp_sqp_rti.h
Expand Up @@ -156,10 +156,10 @@ int ocp_nlp_sqp_rti_workspace_calculate_size(void *config_, void *dims_, void *o
int ocp_nlp_sqp_rti(void *config_, void *dims_, void *nlp_in_, void *nlp_out_,
void *opts_, void *mem_, void *work_);
//
int ocp_nlp_sqp_rti_preparation_step(void *config_, void *dims_,
void ocp_nlp_sqp_rti_preparation_step(void *config_, void *dims_,
void *nlp_in_, void *nlp_out_, void *opts, void *mem_, void *work_);
//
int ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_,
void ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_,
void *nlp_in_, void *nlp_out_, void *opts_, void *mem_, void *work_);
//
void ocp_nlp_sqp_rti_config_initialize_default(void *config_);
Expand Down
2 changes: 2 additions & 0 deletions acados/utils/external_function_generic.c
Expand Up @@ -734,6 +734,7 @@ void external_function_casadi_wrapper(void *self, ext_fun_arg_t *type_in, void *
d_cvt_dvec_to_casadi(in[ii], (double *) fun->args[ii],
(int *) fun->casadi_sparsity_in(ii));
break;

case COLMAJ_ARGS:
d_cvt_colmaj_args_to_casadi(in[ii], (double *) fun->args[ii],
(int *) fun->casadi_sparsity_in(ii));
Expand Down Expand Up @@ -781,6 +782,7 @@ void external_function_casadi_wrapper(void *self, ext_fun_arg_t *type_in, void *
d_cvt_casadi_to_dvec((double *) fun->res[ii], (int *) fun->casadi_sparsity_out(ii),
out[ii]);
break;

case COLMAJ_ARGS:
d_cvt_casadi_to_colmaj_args((double *) fun->res[ii],
(int *) fun->casadi_sparsity_out(ii), out[ii]);
Expand Down
32 changes: 19 additions & 13 deletions docs/interfaces/index.md
Expand Up @@ -49,10 +49,8 @@ Note: This part of the MATLAB/Octave interface does not yet support all features
## Python (templates)

`acados_template` is a Python package that can be used to specify optimal control problems from Python and to generate self-contained C code that uses the acados solvers to solve them.
In comparison with the MATLAB interface for rapid prototyping (see above), it supports less features, but it allows the user to generate a self-contained C library
that can be easily deployed on an embedded system.

The framework is based on templated C files which are rendered from Python using the templating engine `Tera`.
The pip package is based on templated code (C files, Header files and Makefiles), which are rendered from Python using the templating engine `Tera`.
The genereated C code can be compiled into a self-contained C library that can be deployed on an embedded system.

### Optimal Control Problem description
The Python interface relies on the same problem formulation as the MATLAB interface [see here](https://github.com/acados/acados/blob/master/docs/problem_formulation/problem_formulation_ocp_mex.pdf).
Expand All @@ -69,17 +67,25 @@ make install -j4
```
pip3 install <acados_root>/interfaces/acados_template
```
Note: If you are working with a virtual Python environment, use the `pip` corresponding to this Python environment instead of `pip3`.

3. Add the path to the compiled shared libraries `libacados.so, libblasfeo.so, libhpipm.so` to `LD_LIBRARY_PATH` (default path is `<acados_root/lib>`) by running:
```bash
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:"<acados_root>/lib"
```
Tipp: you can add this line to your `.bashrc`/`.zshrc`.

4. Run a Python example to check that everything works.
We suggest to get started with the example
`<acados_root>/examples/acados_python/getting_started/minimal_example_ocp.py`.

(Notice that, you might need to use `pip` instead, if you run, for example, from within a Python virtual environment)
You should now be able to import it as a Python module and use it as shown in the examples in `<acados_root>/examples/acados_template/python/<example_name>/generate_c_code.py`.
5. Optional: Can be done automatically through the interface:
In order to be able to successfully render C code templates, you need to download the `t_renderer` binaries for your platform from <https://github.com/acados/tera_renderer/releases/> and place them in `<acados_root>/bin` (please strip the version and platform from the binaries (e.g.`t_renderer-v0.0.34 -> t_renderer`).
Notice that you might need to make `t_renderer` executable.
Run `export ACADOS_SOURCE_DIR=<acados_root>` such that the location of acados will be known to the Python package at run time.

In order to be able to successfully render C code templates,
you need to download the `t_renderer` binaries for your platform
from <https://github.com/acados/tera_renderer/releases/> and
place them in `<acados_root>/bin` (please strip the version and platform from the binaries (e.g.
`t_renderer-v0.0.34 -> t_renderer`). Notice that you might need to make `t_renderer` executable. Run
`export ACADOS_SOURCE_DIR=<acados_root>` such that the location of acados will be known to the Python
package at run time. Additionally, you will have to make sure that the environment variable `LD_LIBRARY_PATH` contains the path to `libacados.so` (default path is `<acados_root/lib>`). Notice that, if you want to run the examples from a location that differs from '<acados_root>/interfaces/acados_template' or you want the generated Makefile to refer to a specific path (e.g. when cross-compiling or compiling from a location different from the one where you generate the C code), you will have to adapt 'ocp.acados_include_path' and 'ocp.acados_lib_path' accordingly in the generating Python code.
6. Optional: Set `acados_lib_path`, `acados_include_path`.
If you want the generated Makefile to refer to a specific path (e.g. when cross-compiling or compiling from a location different from the one where you generate the C code), you will have to set these paths accordingly in the generating Python code.

For more information contact `@zanellia`.

Expand Down
Expand Up @@ -18,7 +18,7 @@ function check_acados_requirements()
error('Please set up CasADi yourself and try again.');
else
% download CasADi
CasADi_version = '3.4.5';
CasADi_version = '3.5.1';
url = strcat('https://github.com/casadi/casadi/releases/download/',...
CasADi_version, '/');
external_folder = fullfile(acados_dir, 'external');
Expand All @@ -35,7 +35,7 @@ function check_acados_requirements()

if isunix
if verLessThan('matlab', '8.4')
CasADi_version = '3.4.4';
CasADi_version = '3.5.1';
filename = strcat('casadi-linux-matlabR2014a-v', CasADi_version, '.tar.gz');
else % R2014b or later
filename = strcat('casadi-linux-matlabR2014b-v', CasADi_version, '.tar.gz');
Expand Down
Expand Up @@ -131,4 +131,4 @@
print('difference |x0_est - x0_bar|', np.linalg.norm(x0_bar - simXest[0, :]))
print('difference |x_est - x_true|', np.linalg.norm(simXest - simX))

plot_pendulum(h, Fmax, simU, simX, simXest, simY)
plot_pendulum(h, Fmax, simU, simX, simXest, simY, latexify=False)
Expand Up @@ -95,10 +95,10 @@
ocp.solver_options.hessian_approx = 'GAUSS_NEWTON'
ocp.solver_options.integrator_type = 'ERK'
ocp.solver_options.print_level = 0
ocp.solver_options.nlp_solver_type = 'SQP' # SQP_RTI, SQP

# set prediction horizon
ocp.solver_options.tf = Tf
ocp.solver_options.nlp_solver_type = 'SQP' # SQP_RTI

ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json')

Expand All @@ -116,4 +116,6 @@
simU[i,:] = ocp_solver.get(i, "u")
simX[N,:] = ocp_solver.get(N, "x")

plot_pendulum(Tf/N, Fmax, simU, simX)
ocp_solver.print_statistics() # encapsulates: stat = ocp_solver.get_stats("statistics")

plot_pendulum(Tf/N, Fmax, simU, simX, latexify=False)
Expand Up @@ -119,6 +119,7 @@

ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM' # FULL_CONDENSING_QPOASES
ocp.solver_options.hessian_approx = HESSIAN_APPROXIMATION
ocp.solver_options.regularize_method = 'CONVEXIFY'
ocp.solver_options.integrator_type = 'ERK'

ocp.solver_options.qp_solver_cond_N = 5
Expand All @@ -145,5 +146,5 @@
simX[N,:] = ocp_solver.get(N, "x")


plot_pendulum(Tf/N, Fmax, simU, simX)
plot_pendulum(Tf/N, Fmax, simU, simX, latexify=False)

Expand Up @@ -83,4 +83,4 @@
raise Exception('acados returned status {}. Exiting.'.format(status))

# plot results
plot_pendulum(Tf/N, 10, np.zeros((N, nu)), simX)
plot_pendulum(Tf/N, 10, np.zeros((N, nu)), simX, latexify=False)