Manual Jacobians instead of Algorithmic differentiation

Hi.
Is it possible to manually provide the Jacobians for the dynamics, objective function and constraint functions.
In my particular the Jacobians have been derived and implemented in C manually for efficiency and I am looking for a way to provide these to Acados.

Best regards
Thomas Jespersen

Hi,

It is definitely possible in general from a C part of acados.
The following file is relevant for this:
Mostly external_function_generic is realized by external_function_casadi.

If you can call the C function with CasADi variables, you could try to adapt this example:

That being said, this is obviously a more involved way of using acados.
It also depends on which jacobians you want to provide manually and which interface you want to use.

I hope this helps anyway.

Best,
Jonathan

Hi Jonathan.
Thanks for the quick reply. The external_function_param_generic interface is definitely in the right direction.

Ideally, what I’m looking is just a way to supply the cost function and its Jacobian as pure C functions.
That is, be able to define the pure C code behind model.cost_y_expr and model.cost_y_expr_e with no library dependencies, no algorithmic differentiation etc.

With Forces this was not quite possible, but I was able to achieve something very close by using their External Function interface: https://forces.embotech.com/Documentation/high_level_interface/index.html#expected-function-signature

void myfunctions (
    double *x, /* primal vars */
    double *y, /* eq. constraint multiplers */
    double *l, /* ineq . constraint multipliers */
    double *p, /* runtime parameters */
    double *f, /* objective function ( incremented in this function ) */
    double *nabla_f , /* gradient of objective function */
    double *c, /* dynamics */
    double *nabla_c , /* Jacobian of the dynamics ( column major ) */
    double *h, /* inequality constraints */
    double *nabla_h , /* Jacobian of inequality constraints ( column major ) */
    double *H, /* Hessian ( column major ) */
    int stage, /* stage number (0 indexed ) */
    int iteration /* Solver iteration count */
)

Although this requires everything to be specified in that C function it is acceptable for now.

So the question is if something similar can be achieved with Acados? So without using CasADi.
Both the example you provided and what I have found at https://github.com/acados/acados/tree/master/experimental/interfaces/matlab/external_function_generation is using CasADi. For the latter, is the generated code used in another example anywhere?

Maybe I can achieve the above with ocp_nlp_cost_external_model_set with the field set to ext_cost_fun and ext_cost_fun_jac respectively? If so I would greatly appreciate some directions or hints, especially on the prerequisites before calling this function?
Or maybe this is exactly the example I am looking for: https://github.com/acados/acados/blob/master/examples/c/no_interface_examples/mass_spring_nmpc_example.c#L158-L262 ?

PS: The main reason for not using CasADi is that I’m unable to use CasADi since the function evaluations relies on an external array of data - which I don’t expect to be able to set as an online parameter :wink:

Again, thanks for your help.

Kind regards
Thomas Jespersen

Hi Thomas,

sorry for the late reply.
I was not aware of this interface in Forces, but it would be really nice to have something like this in acados.

As for now, this is unfortunately not the case, and one would has to provide functions that follow the conventions of the corresponding acados module, similarly to what you found here: https://github.com/acados/acados/blob/master/examples/c/no_interface_examples/mass_spring_nmpc_example.c#L158-L262
This will not be a bit different for the dynamics.
Regarding them: Do you want to use an acados integrator or provide discrete dynamics.

Note, there was some effort to document the convention on external functions of the modules: https://github.com/acados/acados/blob/interface_fixes/utils/convention_about_external_functions.txt

As for prerequisites on how to set the model function, you indeed have to just supply an object of type external_function_generic that implements the evaluate function.

Why do you think you cannot supply this data as online parameters?