Is there a way to give a changing reference value over the horizon directly or does it have to be passed over with userparam (the hacky way)?
The reason I am asking is that it is possible in ACADO and is claimed to be benificial in the case of a inverted pendulum swingup in ([1], under heading 6., paragraph Choice of Reference) . Is that also to expect with GRAMPC?
[1]: From linear to nonlinear MPC: bridging the gap via the real-time iteration, 10.1080/00207179.2016.1222553,
If you would like to refer to this comment somewhere else in this project, copy and paste the following link:
ctypeRNum* t_switch = pcost + NPCOST + NPCONSTR + 1;
typeRNum x_des_r[NNX];
if(t >= t_switch[0]) // t is integration time over horizon starting at 0, so t_switch has to be changed based on the current iteration step
{
x_des_r[0] = xdes[0];
x_des_r[1] = xdes[1];
x_des_r[2] = xdes[2];
x_des_r[3] = xdes[3];
}
else
{
x_des_r[0] = 0;
x_des_r[1] = 0;
x_des_r[2] = 0;
x_des_r[3] = 0;
}
where t_switch is passed over with userparam and switches to the reference value when the simulation time (over the horizon) reaches that point.
t_switch is reduced in the matlab script to push the point of reference change further to the beginning over time.
If you would like to refer to this comment somewhere else in this project, copy and paste the following link:
if the setpoint is time-varying and known in advance, it is definitely beneficial to consider it in the prediction of the MPC. However, since there are many different ways for representing such a reference (discrete waypoints, polynomials, splines, ...), GRAMPC supports only the typical usecase of constant setpoints via xdes, udes and all other scenarios can be implemented via userparam. Note that this is not intended as a "hacky way", but allows the user to realize many different applications without increasing the complexity of GRAMPC itself. Of course, it can become a bit confusing when userparm is interpreted as array of doubles. However, when used directly in C, userparam is better used for a structure with separate fields for each parameter.
That said, your solution looks fine. The only thing one should consider is that the time passed to the cost functions is always the internal prediction time in [0, T]. Therefore, if the global time is required, the sampling step t_k has to be passed in via userparam.
Regards,
Andreas
If you would like to refer to this comment somewhere else in this project, copy and paste the following link:
I didn't mean that it is not a good solution, in fact I find GRAMPC relatively easy to understand as end user because the source code is well structured.
The approach I described before works well in the simulation via Matlab.
However, for my realtime implementation I am using simulink and the sfunction you provide with GRAMPC.
I need to pass over the switch time as part of my userparam vector but the sfunction has no input for the userparameter.
I figured out that I could modify the file grampcrunSfct.c to give another input port for the sfunction. Then in mdlOutputs the current parameters are set with:
/* set the current quantitites */
grampc_setparam_real_vector(grampc, "x0", x0);
grampc_setparam_real(grampc, "t0", t0[0]);
grampc_setparam_real_vector(grampc, "xdes", xdes);
grampc_setparam_real_vector(grampc, "udes", udes);
for your information, the userparam vector has been added as additional input to the S-function in version 2.2 of GRAMPC. Thus, it should no longer be necessary to modify grampc_run_Sfct.c for your usecase.
Regards,
Andreas
If you would like to refer to this comment somewhere else in this project, copy and paste the following link:
Is there a way to give a changing reference value over the horizon directly or does it have to be passed over with userparam (the hacky way)?
The reason I am asking is that it is possible in ACADO and is claimed to be benificial in the case of a inverted pendulum swingup in ([1], under heading 6., paragraph Choice of Reference) . Is that also to expect with GRAMPC?
[1]: From linear to nonlinear MPC: bridging the gap via the real-time iteration, 10.1080/00207179.2016.1222553,
I implemented it like this:
where t_switch is passed over with userparam and switches to the reference value when the simulation time (over the horizon) reaches that point.
t_switch is reduced in the matlab script to push the point of reference change further to the beginning over time.
Hello hcl734,
if the setpoint is time-varying and known in advance, it is definitely beneficial to consider it in the prediction of the MPC. However, since there are many different ways for representing such a reference (discrete waypoints, polynomials, splines, ...), GRAMPC supports only the typical usecase of constant setpoints via xdes, udes and all other scenarios can be implemented via userparam. Note that this is not intended as a "hacky way", but allows the user to realize many different applications without increasing the complexity of GRAMPC itself. Of course, it can become a bit confusing when userparm is interpreted as array of doubles. However, when used directly in C, userparam is better used for a structure with separate fields for each parameter.
That said, your solution looks fine. The only thing one should consider is that the time passed to the cost functions is always the internal prediction time in [0, T]. Therefore, if the global time is required, the sampling step t_k has to be passed in via userparam.
Regards,
Andreas
Hello Andreas,
I didn't mean that it is not a good solution, in fact I find GRAMPC relatively easy to understand as end user because the source code is well structured.
The approach I described before works well in the simulation via Matlab.
However, for my realtime implementation I am using simulink and the sfunction you provide with GRAMPC.
I need to pass over the switch time as part of my userparam vector but the sfunction has no input for the userparameter.
I figured out that I could modify the file grampcrunSfct.c to give another input port for the sfunction. Then in mdlOutputs the current parameters are set with:
So I would add the following in mdlOutputs :
just as documentation if somebody will need it
Hello hcl734,
for your information, the userparam vector has been added as additional input to the S-function in version 2.2 of GRAMPC. Thus, it should no longer be necessary to modify grampc_run_Sfct.c for your usecase.
Regards,
Andreas