Appendix#

In addition to a list of all parameters and algorithmic options of GRAMPC, this appendix contains a short description of the structure variable grampc. Essential C functions of the GRAMPC project are also listed.

List of parameters#

Table 3 gives an overview of the problem-specific parameters of GRAMPC in terms of the parameter name and type as well as the admissible range and default values (if available), whereby the symbol \(\text{e}_n = [1,\ldots,1]^\mathsf{T}\in \mathbb{R}^n\) denotes an \(n\)-dimensional column vector.

Table 3 Problem-specific parameters.#

Parameter name

Type

Allowed values

Default

x0

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Nx}\)

xdes

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Nx}\)

u0

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Nx}\)

udes

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Nx}\)

umax

typeRNum*

\((-\infty, \infty)\)

\(+\infty\cdot \mathrm{e}_{Nx}\)

umin

typeRNum*

\((-\infty, \infty)\)

\(-\infty\cdot \mathrm{e}_{Nx}\)

p0

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Nx}\)

pmax

typeRNum*

\((-\infty, \infty)\)

\(+\infty\cdot \mathrm{e}_{Nx}\)

pmin

typeRNum*

\((-\infty, \infty)\)

\(-\infty\cdot \mathrm{e}_{Nx}\)

Thor

typeRNum

\((0, \infty)\)

To be provided

Tmax

typeRNum

\((0, \infty)\)

\(10^8\)

Tmin

typeRNum

\((0, \infty)\)

\(10^{-8}\)

dt

typeRNum

\((0, \infty)\)

To be provided

t0

typeRNum

\((0, \infty)\)

\(0\)

userparam (in C)

void*

User-defined

NULL

userparam (in MATLAB)

typeRNum*

\((-\infty, \infty)\)

[]

A description of all parameters is as follows (see also Problem formulation and implementation):

  • x0: Initial state vector \(\mb{x}(t_0)=\mb{x}_0\) at the corresponding sampling time \(t_0\).

  • xdes: Desired (constant) setpoint vector for the state variables \(\mb{x}\).

  • u0: Initial value of the control vector \(\mb{u}(t) = \mb{u}_0 = \text{const.}\), \(t \in [0,T]\) that is used in the first iteration of GRAMPC.

  • udes: Desired (constant) setpoint vector for the control variables \(\mb{u}\).

  • umin, umax : Lower and upper bounds for the control variables \(\mb{u}\).

  • p0: Initial value of the parameter vector \(\mb{p} = \mb{p}_0\) that is used in the first iteration of GRAMPC.

  • pmin, pmax: Lower and upper bounds for the parameters \(\mb{p}\).

  • Thor: Prediction horizon \(T\) or initial value if the end time is optimized.

  • Tmin, Tmax: Lower and upper bound for the prediction horizon \(T\).

  • dt: Sampling time \(\Delta t\) of the considered system for model predictive control or moving horizon estimation. Required for prediction of next state grampc.sol.xnext and for the control shift, see Control shift.

  • t0: Current sampling instance \(t_0\) that is provided in the grampc.param structure.

  • userparam: Further problem-specific parameters, e.g. system parameters or weights in the cost functions that are passed to the problem functions via a void-pointer in C or typeRNum array in MATLAB.

List of options#

Table 4 gives an overview of the algorithmic options of GRAMPC in terms of the option name and type as well as the allowed and the default values (if available).

Table 4 Algorithmic Options.#

Option name

Type

Allowed values

Default

Nhor

typeInt

\([2, \infty)\)

\(30\)

MaxGradIter

typeInt

\([1, \infty)\)

\(2\)

MaxMultIter

typeInt

\([1, \infty)\)

\(1\)

ShiftControl

typeChar*

on/ off

on

IntegralCost

typeChar*

on/ off

on

TerminalCost

typeChar*

on/ off

on

IntegratorCost

typeChar*

trapezoidal/ simpson/ discrete

trapezoidal

Integrator

typeChar*

erk1/ erk2/ erk3/ erk4/ discrete/ ruku45/ rodas

erk2

IntegratorRelTol

typeRNum

\((0, \infty)\)

\(10^{-6}\)

IntegratorAbsTol

typeRNum

\((0, \infty)\)

\(10^{-8}\)

IntegratorMinStepSize

typeRNum

\((0, \infty)\)

eps

IntegratorMaxSteps

typeInt

\([1, \infty)\)

\(10^{8}\)

FlagsRodas

typeInt*

see description

see description

LineSearchType

typeChar*

adaptive/ explicit1/ explicit2

explicit2

LineSearchExpAutoFallback

typeChar*

on/ off

on

LineSearchMax

typeRNum

\((0, \infty)\)

\(0.75\)

LineSearchMin

typeRNum

\((0, \infty)\)

\(10^{-10}\)

LineSearchInit

typeRNum

\((0, \infty)\)

\(10^{-4}\)

LineSearchAdaptAbsTol

typeRNum

\([0, \infty)\)

\(10^{-6}\)

LineSearchAdaptFactor

typeRNum

\((1, \infty)\)

\(3/2\)

LineSearchIntervalTol

typeRNum

\((0, 0.5)\)

\(0.1\)

LineSearchIntervalFactor

typeRNum

\((0, 1)\)

\(0.85\)

OptimControl

typeChar*

on/ off

on

OptimParam

typeChar*

on/ off

off

OptimParamLineSearchFactor

typeRNum

\((0, \infty)\)

\(1.0\)

OptimTime

typeChar*

on/ off

off

OptimTimeLineSearchFactor

typeRNum

\((0, \infty)\)

\(1.0\)

ScaleProblem

typeChar*

on/ off

off

xScale

typeRNum*

\((-\infty, \infty)\)

\(\mathrm{e}_{Nx}\)

xOffset

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Nx}\)

uScale

typeRNum*

\((-\infty, \infty)\)

\(\mathrm{e}_{Nu}\)

uOffset

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Nu}\)

pScale

typeRNum*

\((-\infty, \infty)\)

\(\mathrm{e}_{Np}\)

pOffset

typeRNum*

\((-\infty, \infty)\)

\(0\cdot \mathrm{e}_{Np}\)

TScale

typeRNum

\((0, \infty)\)

\(1.0\)

TOffset

typeRNum

\((-\infty, \infty)\)

\(0.0\)

JScale

typeRNum

\((0, \infty)\)

\(1.0\)

cScale

typeRNum*

\((-\infty, \infty)\)

\(\mathrm{e}_{Nc}\)

EqualityConstraints

typeChar*

on/ off

on

InequalityConstraints

typeChar*

on/ off

on

TerminalEqualityConstraints

typeChar*

on/ off

on

TerminalInequalityConstraints

typeChar*

on/ off

on

ConstraintsHandling

typeChar*

extpen/ auglag

auglag

ConstraintsAbsTol

typeRNum*

\((0, \infty)\)

\(10^{-4}\mathrm{e}_{Nc}\)

MultiplierMax

typeRNum

\((0, \infty)\)

\(10^{6}\)

MultiplierDampingFactor

typeRNum

\([0, 1]\)

\(0.0\)

PenaltyMax

typeRNum

\((0, \infty)\)

\(10^6\)

PenaltyMin

typeRNum

\((0, \infty)\)

\(10^0\)

PenaltyIncreaseFactor

typeRNum

\([1, \infty)\)

\(1.05\)

PenaltyDecreaseFactor

typeRNum

\([0, 1]\)

\(0.95\)

PenaltyIncreaseThreshold

typeRNum

\([0, \infty)\)

\(1.0\)

AugLagUpdateGradientRelTol

typeRNum

\([0, 1]\)

\(10^{-2}\)

ConvergenceCheck

typeChar*

on/ off

off

ConvergenceGradientRelTol

typeRNum

\([0, 1]\)

\(10^{-6}\)

A description of all options is as follows:

  • Nhor: Number of discretization points within the time interval \([0,T]\).

  • MaxMultIter: Sets the maximum number of augmented Lagrangian iterations \(i_\text{max} \geq 1\). If the option ConvergenceCheck is activated, the algorithm evaluates the convergence criterion and terminates if the inner minimization converged and all constraints are satisfied within the tolerance defined by ConstraintsAbsTol.

  • MaxGradIter: If the option ConvergenceCheck is activated, the algorithm terminates the inner loop as soon as the convergence criterion is fulfilled.

  • ShiftControl: Activates or deactivates the shifting of the control trajectory and the adaptation of \(T\) in case of a free end time, i.e., if OptimTime is active.

  • IntegralCost, TerminalCost: Indicate if the integral and/or terminal cost functions are defined.

  • IntegratorCost: This option specifies the integration scheme for the cost functionals. Possible values are trapezoidal, simpson and discrete.

Changed in version v2.3: Fixed typo in trapezoidal option. Renamed euler to erk1 and heun to erk2. Removed modeuler. Added erk3 and erk4.

  • Integrator: This option specifies the integration scheme for the system and adjoint dynamics. Possible values are erk1, erk2, erk3, erk4, discrete with fixed step size and ruku45, rodas with variable step size.

  • IntegratorMinStepSize: Minimum step size for RODAS and the Runge-Kutta integrator.

  • IntegratorMaxSteps: Maximum number of steps for RODAS and the Runge-Kutta integrator.

  • IntegratorRelTol: Relative tolerance for RODAS and the Runge-Kutta integrator with variable step size. Note that this option may be insignificant if the minimum step size is chosen too high or the maximum number of steps is set too low.

  • IntegratorAbsTol: Absolute tolerance for RODAS and the Runge-Kutta integrator with variable step size. Note that this option may be insignificant if the minimum step size is chosen too high or the maximum number of steps is set too low.

  • FlagsRodas: Vector with the elements [IFCN, IDFX, IJAC, IMAS, MLJAC, MUJAC, MLMAS, MUMAS] that is passed to the integrator RODAS, see Integration of semi-implicit ODEs and DAEs (RODAS) for a description of the single entries.

  • LineSearchType: This option selects either the adaptive line search strategy (value adaptive) or the explicit approach (value explicit1 or explicit2).

  • LineSearchExpAutoFallback: If this option is activated, the automatic fallback strategy is used in the case that the explicit formulas result in negative step sizes.

  • LineSearchMax: This option sets the maximum value \(\alpha_{\max}\) of the step size \(\alpha\).

  • LineSearchMin: This option sets the minimum value \(\alpha_{\min}\) of the step size \(\alpha\).

  • LineSearchInit: Indicates the initial value \(\alpha_{\text{init}}>0\) for the step size \(\alpha\). If the adaptive line search is used, the sample point \(\alpha_2\) is set to \(\alpha_2 = \alpha_{\text{init}}\).

  • LineSearchAdaptAbsTol: This option sets the absolute tolerance \(\varepsilon_{\phi}\) of the difference in costs at the interval bounds \(\alpha_1\) and \(\alpha_2\). If the difference in the (scaled) costs on these bounds falls below \(\varepsilon_{\phi}\), the adaption of the interval is stopped in order to avoid oscillations.

  • LineSearchAdaptFactor: This option sets the adaptation factor \(\kappa > 1\) in (8) that determines how much the line search interval can be adapted from one gradient iteration to the next.

  • LineSearchIntervalTol: This option sets the interval tolerance \(\varepsilon_{\alpha} \in (0,0.5)\) in (8) that determines for which values of \(\alpha\) the adaption is performed.

  • LineSearchIntervalFactor: This option sets the interval factor \(\beta \in (0,1)\) that specifies the interval bounds \([\alpha_1,\alpha_3]\) according to \(\alpha_1 = \alpha_2 (1 - \beta)\) and \(\alpha_3 = \alpha_2 (1 + \beta)\), whereby the mid sample point is initialized as \(\alpha_2 = \alpha_\text{init}\).

  • OptimControl: Specifies whether the cost functional should be minimized with respect to the control variable \(\mb{u}\).

  • OptimParam: Specifies whether the cost functional should be minimized with respect to the optimization parameters \(\mb{p}\).

  • OptimParamLineSearchFactor: This option sets the adaptation factor \(\gamma_{\mb{p}}\) that weights the update of the parameter vector \(\mb{p}\) against the update of the control \(\mb{u}\).

  • OptimTime: Specifies whether the cost functional should be minimized with respect the horizon length \(T\) (free end time problem) or if \(T\) is kept constant.

  • OptimTimeLineSearchFactor: This option sets the adaptation factor \(\gamma_{T}\) that weights the update of the end time \(T\) against the update of the control \(\mb{u}\).

  • ScaleProblem: Activates or deactivates scaling. Note that GRAMPC requires more computation time if scaling is active.

  • xScale, xOffset: Scaling factors \(\mb{x}_\text{scale}\) and offsets \(\mb{x}_\text{offset}\) for each state variable.

  • uScale, uOffset: Scaling factors \(\mb{u}_\text{scale}\) and offsets \(\mb{u}_\text{offset}\) for each control variable.

  • pScale, pOffset: Scaling factors \(\mb{p}_\text{scale}\) and offsets \(\mb{p}_\text{offset}\) for each parameter.

  • TScale, TOffset: Scaling factor \(T_\text{scale}\) and offset \(T_\text{offset}\) for the horizon length.

  • JScale: Scaling factor \(J_\text{scale}\) for the cost functional.

  • cScale: Scaling factors \(\mb{c}_\text{scale}\) for each state constraint. The elements of the vector refer to the equality, inequality, terminal equality and terminal inequality constraints.

  • EqualityConstraints: Equality constraints \(\mb{g}(\mb{x}(t), \mb{u}(t), \mb{p}, t) = \mb{0}\) can be disabled by the option value off.

  • InequalityConstraints: To disable inequality constraints \(\mb{h}(\mb{x}(t), \mb{u}(t), \mb{p}, t) \le \mb{0}\), set this option to off.

  • TerminalEqualityConstraints: To disable terminal equality constraints \(\mb{g}_T(\mb{x}(T), \mb{p}, T) = \mb{0}\), set this option to off.

  • TerminalInequalityConstraints: To disable terminal inequality constraints \(\mb{h}_T(\mb{x}(T), \mb{p}, T) \le \mb{0}\), set this option to off.

  • ConstraintsHandling: State constraints are handled either by means of the augmented Lagrangian approach (option value auglag) or as soft constraints by outer penalty functions (option value extpen).

  • ConstraintsAbsTol: Thresholds \((\mb{\varepsilon_{\mb{g}}}, \mb{\varepsilon_{\mb{h}}}, \mb{\varepsilon_{\mb{g_T}}}, \mb{\varepsilon_{\mb{h_T}}}) \in \mathbb{R}^{N_{c}}\) for the equality, inequality, terminal equality, and terminal inequality constraints.

  • MultiplierMax: Upper bound \(\mu_\text{max}\) and lower bound \(-\mu_\text{max}\) for the Lagrangian multpliers.

  • MultiplierDampingFactor:Damping factor \(\rho \in [0,1)\) for the multiplier update.

  • PenaltyMax: This option sets the upper bound \(c_\text{max}\) of the penalty parameters.

  • PenaltyMin: This option sets the lower bound \(c_\text{min}\) of the penalty parameters.

  • PenaltyIncreaseFactor: This option sets the factor \(\beta_\text{in}\) by which penalties are increased.

  • PenaltyDecreaseFactor: This option sets the factor \(\beta_\text{de}\) by which penalties are decreased.

  • PenaltyIncreaseThreshold: This option sets the factor \(\gamma_\text{in}\) that rates the progress in the constraints between the last two iterates.

  • AugLagUpdateGradientRelTol: Threshold \(\varepsilon_\text{rel,u}\) for the maximum relative gradient of the inner minimization problem.

  • ConvergenceCheck: This option activates the convergence criterion. Otherwise, the inner and outer loops always perform the maximum number of iterations, see the options MaxGradIter and MaxMultIter.

  • ConvergenceGradientRelTol: This option sets the threshold \(\varepsilon_\text{rel,c}\) for the maximum relative gradient of the inner minimization problem that is used in the convergence criterion. Note that this threshold is different from the one that is used in the update of multipliers and penalties.

GRAMPC data types#

The following lines list the data types of GRAMPC. Note that these data types define the structure variable grampc including the substructures sol, param, opt, rws, and userparam, also see Initialization of GRAMPC.

Listing 10 GRAMPC main structure.#
typedef struct
{
    typeGRAMPCparam *param;
    typeGRAMPCopt *opt;
    typeGRAMPCsol *sol;
    typeGRAMPCrws *rws;
    typeUSERPARAM *userparam;
} typeGRAMPC;
Listing 11 GRAMPC parameter structure.#
typedef struct
{
    typeInt Nx;
    typeInt Nu;
    typeInt Np;
    typeInt Ng;
    typeInt Nh;
    typeInt NgT;
    typeInt NhT;
    typeInt Nc;

    typeRNum *x0;
    typeRNum *xdes;

    typeRNum *u0;
    typeRNum *udes;
    typeRNum *umax;
    typeRNum *umin;

    typeRNum *p0;
    typeRNum *pmax;
    typeRNum *pmin;

    typeRNum Thor;
    typeRNum Tmax;
    typeRNum Tmin;

    typeRNum dt;
    typeRNum t0;
} typeGRAMPCparam;
Listing 12 GRAMPC option structure.#
typedef struct
{
    typeInt Nhor;
    typeInt MaxGradIter;
    typeInt MaxMultIter;
    typeInt ShiftControl;

    typeInt TimeDiscretization;

    typeInt IntegralCost;
    typeInt TerminalCost;
    typeInt IntegratorCost;

    typeInt  Integrator;
    typeRNum IntegratorRelTol;
    typeRNum IntegratorAbsTol;
    typeRNum IntegratorMinStepSize;
    typeInt  IntegratorMaxSteps;
    typeInt  *FlagsRodas;

    typeInt  LineSearchType;
    typeInt  LineSearchExpAutoFallback;
    typeRNum LineSearchMax;
    typeRNum LineSearchMin;
    typeRNum LineSearchInit;
    typeRNum LineSearchIntervalFactor;
    typeRNum LineSearchAdaptFactor;
    typeRNum LineSearchIntervalTol;

    typeInt  OptimControl;
    typeInt  OptimParam;
    typeRNum OptimParamLineSearchFactor;
    typeInt  OptimTime;
    typeRNum OptimTimeLineSearchFactor;

    typeInt  ScaleProblem;
    typeRNum *xScale;
    typeRNum *xOffset;
    typeRNum *uScale;
    typeRNum *uOffset;
    typeRNum *pScale;
    typeRNum *pOffset;
    typeRNum TScale;
    typeRNum TOffset;
    typeRNum JScale;
    typeRNum *cScale;

    typeInt  EqualityConstraints;
    typeInt  InequalityConstraints;
    typeInt  TerminalEqualityConstraints;
    typeInt  TerminalInequalityConstraints;
    typeInt  ConstraintsHandling;
    typeRNum *ConstraintsAbsTol;

    typeRNum MultiplierMax;
    typeRNum MultiplierDampingFactor;
    typeRNum PenaltyMax;
    typeRNum PenaltyMin;
    typeRNum PenaltyIncreaseFactor;
    typeRNum PenaltyDecreaseFactor;
    typeRNum PenaltyIncreaseThreshold;
    typeRNum AugLagUpdateGradientRelTol;

    typeInt  ConvergenceCheck;
    typeRNum ConvergenceGradientRelTol;

} typeGRAMPCopt;
Listing 13 GRAMPC solution structure.#
typedef struct
{
    typeRNum *xnext;
    typeRNum *unext;
    typeRNum *pnext;
    typeRNum Tnext;
    typeRNum *J;
    typeRNum cfct;
    typeRNum pen;
    typeInt *iter;
    typeInt status;
} typeGRAMPCsol;
Listing 14 GRAMPC real workspace structure.#
typedef struct
{
    typeRNum *t;
    typeRNum *tls;

    typeRNum *x;
    typeRNum *adj;
    typeRNum *dcdx;

    typeRNum *u;
    typeRNum *uls;
    typeRNum *uprev;
    typeRNum *gradu;
    typeRNum *graduprev;
    typeRNum *dcdu;

    typeRNum *p;
    typeRNum *pls;
    typeRNum *pprev;
    typeRNum *gradp;
    typeRNum *gradpprev;
    typeRNum *dcdp;

    typeRNum T;
    typeRNum Tprev;
    typeRNum gradT;
    typeRNum gradTprev;
    typeRNum dcdt;

    typeRNum *mult;
    typeRNum *pen;
    typeRNum *cfct;
    typeRNum *cfctprev;
    typeRNum *cfctAbsTol;

    typeRNum *lsAdapt;
    typeRNum *lsExplicit;
    typeRNum *rwsScale;
    typeInt  lrwsGeneral;
    typeRNum *rwsGeneral;

    typeInt  lworkRodas;
    typeInt  liworkRodas;
    typeRNum *rparRodas;
    typeInt  *iparRodas;
    typeRNum *workRodas;
    typeInt  *iworkRodas;
} typeGRAMPCrws;

GRAMPC function interface#

The main C functions for the usage of GRAMPC are listed below.

Listing 15 File grampc_init:#
void grampc_init(typeGRAMPC **grampc, typeUSERPARAM *userparam);
void grampc_free(typeGRAMPC **grampc);
Listing 16 File grampc_run:#
void grampc_run(const typeGRAMPC *grampc);
Listing 17 File grampc_setparam:#
void grampc_setparam_real(const typeGRAMPC *grampc, const typeChar *paramName, ctypeRNum paramValue);

void grampc_setparam_real_vector(const typeGRAMPC *grampc, const typeChar *paramName, ctypeRNum *paramValue);

void grampc_printparam(const typeGRAMPC *grampc);
Listing 18 File grampc_setopt:#
void grampc_setopt_real(const typeGRAMPC *grampc, const typeChar *optName, ctypeRNum optValue);

void grampc_setopt_int(const typeGRAMPC *grampc, const typeChar *optName, ctypeInt optValue);

void grampc_setopt_string(const typeGRAMPC *grampc, const typeChar *optName, const typeChar *optValue);

void grampc_setopt_real_vector(const typeGRAMPC *grampc, const typeChar *optName, ctypeRNum *optValue);

void grampc_setopt_int_vector(const typeGRAMPC *grampc, const typeChar *optName, ctypeInt *optValue);

void grampc_printopt(const typeGRAMPC *grampc);
Listing 19 File grampc_mess:#
/** estimates PenaltyMin on basis of the first MPC iteration **/
typeInt grampc_printstatus(ctypeInt status, ctypeInt level);
Listing 20 File grampc_util:#
/** estimates PenaltyMin on basis of the first MPC iteration **/
typeInt grampc_estim_penmin(typeGRAMPC *grampc, ctypeInt rungrampc);
Listing 21 File probfct:#
/** OCP dimensions: states (Nx), controls (Nu), parameters (Np), equalities (Ng), 
    inequalities (Nh), terminal equalities (NgT), terminal inequalities (NhT) **/
void ocp_dim(typeInt *Nx, typeInt *Nu, typeInt *Np, typeInt *Ng, typeInt *Nh, typeInt *NgT, typeInt *NhT, typeUSERPARAM *userparam);


/** System function f(t,x,u,p,param,userparam) 
    ------------------------------------ **/
void ffct(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian df/dx multiplied by vector vec, i.e. (df/dx)^T*vec or vec^T*(df/dx) **/
void dfdx_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian df/du multiplied by vector vec, i.e. (df/du)^T*vec or vec^T*(df/du) **/
void dfdu_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian df/dp multiplied by vector vec, i.e. (df/dp)^T*vec or vec^T*(df/dp) **/
void dfdp_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);


/** Integral cost l(t,x(t),u(t),p,param,userparam) 
    -------------------------------------------------- **/
void lfct(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Gradient dl/dx **/
void dldx(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Gradient dl/du **/
void dldu(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Gradient dl/dp **/
void dldp(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);


/** Terminal cost V(T,x(T),p,param,userparam) 
    ---------------------------------------- **/
void Vfct(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Gradient dV/dx **/
void dVdx(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Gradient dV/dp **/
void dVdp(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Gradient dV/dT **/
void dVdT(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);


/** Equality constraints g(t,x(t),u(t),p,param,userparam) = 0 
    --------------------------------------------------- **/
void gfct(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dg/dx multiplied by vector vec, i.e. (dg/dx)^T*vec or vec^T*(dg/dx) **/
void dgdx_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dg/du multiplied by vector vec, i.e. (dg/du)^T*vec or vec^T*(dg/du) **/
void dgdu_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dg/dp multiplied by vector vec, i.e. (dg/dp)^T*vec or vec^T*(dg/dp) **/
void dgdp_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);


/** Inequality constraints h(t,x(t),u(t),p,param,userparam) <= 0 
    ------------------------------------------------------ **/
void hfct(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dh/dx multiplied by vector vec, i.e. (dh/dx)^T*vec or vec^T*(dg/dx) **/
void dhdx_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dh/du multiplied by vector vec, i.e. (dh/du)^T*vec or vec^T*(dg/du) **/
void dhdu_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dh/dp multiplied by vector vec, i.e. (dh/dp)^T*vec or vec^T*(dg/dp) **/
void dhdp_vec(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);


/** Terminal equality constraints gT(T,x(T),p,param,userparam) = 0 
    -------------------------------------------------------- **/
void gTfct(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dgT/dx multiplied by vector vec, i.e. (dgT/dx)^T*vec or vec^T*(dgT/dx) **/
void dgTdx_vec(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dgT/dp multiplied by vector vec, i.e. (dgT/dp)^T*vec or vec^T*(dgT/dp) **/
void dgTdp_vec(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dgT/dT multiplied by vector vec, i.e. (dgT/dT)^T*vec or vec^T*(dgT/dT) **/
void dgTdT_vec(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);


/** Terminal inequality constraints hT(T,x(T),p,param,userparam) <= 0 
    ----------------------------------------------------------- **/
void hTfct(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dhT/dx multiplied by vector vec, i.e. (dhT/dx)^T*vec or vec^T*(dhT/dx) **/
void dhTdx_vec(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dhT/dp multiplied by vector vec, i.e. (dhT/dp)^T*vec or vec^T*(dhT/dp) **/
void dhTdp_vec(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian dhT/dT multiplied by vector vec, i.e. (dhT/dT)^T*vec or vec^T*(dhT/dT) **/
void dhTdT_vec(typeRNum *out, ctypeRNum T, ctypeRNum *x, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);


/** Additional functions required for semi-implicit systems 
    M*dx/dt(t) = f(t,x(t),u(t),p,param,userparam) using the solver RODAS 
    ------------------------------------------------------- **/
/** Jacobian df/dx in vector form (column-wise) **/
void dfdx(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian df/dx in vector form (column-wise) **/
void dfdxtrans(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian df/dt **/
void dfdt(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Jacobian d(dH/dx)/dt  **/
void dHdxdt(typeRNum *out, ctypeRNum t, ctypeRNum *x, ctypeRNum *u, ctypeRNum *p, ctypeRNum *vec, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Mass matrix in vector form (column-wise, either banded or full matrix) **/
void Mfct(typeRNum *out, const typeGRAMPCparam *param, typeUSERPARAM *userparam);
/** Transposed mass matrix in vector form (column-wise, either banded or full matrix) **/
void Mtrans(typeRNum *out, const typeGRAMPCparam *param, typeUSERPARAM *userparam);