Error while compiling simulink model for dSpace Scalexio

Hey guys,

I successfully constructed an NMPC with an ACADOS S-Function running in a closed-loop model in Simulink.
Now I am trying to compile it with dSpace ConfigurationDesk to the real time system Scalexio and make it run on this.
While compiling it throws loads of errors for the ACADOS S-Function:

Making Makefile “CfgDeskmpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.mk” …
mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.c: In function ‘rt_powd_snf’:
mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.c:214:11: error: implicit declaration of function ‘fabs’ [-Werror=implicit-function-declaration]
Compiling “D:\ACADOS_C_Code_Test\ConfigDesk\NMPC_AW_Reduced\Components\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced_dsrt\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.c” …
tmp = fabs(u0);
Compiling “D:\ACADOS_C_Code_Test\ConfigDesk\Models\acados\examples\acados_matlab_octave\c_generated_code\acados_solver_sfunction_ocp_model.c” …
^
Compiling “D:\ACADOS_C_Code_Test\ConfigDesk\NMPC_AW_Reduced\Components\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced_dsrt\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced_dsrtmdlfcn.c” …
Compiling “D:\ACADOS_C_Code_Test\ConfigDesk\NMPC_AW_Reduced\Components\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced_dsrt\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced_dsrtmf.c” …
mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.c:214:11: warning: incompatible implicit declaration of built-in function ‘fabs’
mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.c:214:11: note: include ‘<math.h>’ or provide a declaration of ‘fabs’
Compiling “D:\ACADOS_C_Code_Test\ConfigDesk\NMPC_AW_Reduced\Components\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced_dsrt\mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced_dsrttf.c” …
mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.c:241:11: error: implicit declaration of function ‘sqrt’ [-Werror=implicit-function-declaration]
y = sqrt(u0);

These errors occur for all the mathematical operations I am using in the acados S-Function (sin, cos, etc.). Math.h is included and I tried to include it again manually via custom code.
I dont think math.h is the problem, I think its more the missing casadi operators after rendering?
Do I have to include the casadi lib / files seperately? I thought they would be included with the ACADOS files.

Do you have any suggestions? I have a deadline in two weeks… :smiley:

Greets and thanks,
Alex

Hi Alex,

Your output also says: “warning: incompatible implicit declaration of built-in function ‘fabs’”. Could it be a casting problem? Also you might need to provide the ‘-lm’ argument to instruct the linker to link against the math library. Honestly, I do not think it’s a CasADi-related problem - I might be wrong though :slight_smile:

Cheers,
Andrea

Hi Andrea,

thanks for your reply. The compiler takes the math.h file from its own src folder. And it doesnt give any warning that it is not found. And the right directories for these src files are being given to the compiler, as I could see in the MAKEFILE.

I think your suggestion of it being a casting problem is a really good one. This would explain the behaviour. The variables being treated at the line of the error should be casadi.mx files, maybe this produces a casting error.
How am I able to check if the casadi functions / declarations / wrappers are all implemented? Which of those is responsible for the casadi data types?
Any clue?

EDIT:
There are some errors being thrown by the compiler now while calling the “math.h” functions “sin”, “cos”, etc. At this point in the acados MPC code it uses the casadi realT datatypes.
I think there should be a problem regarding this?
<Error: “mpc_aw_v08_deadtime_SFUN_ac_2018b_reduced.c:241:11: warning: incompatible implicit declaration of built-in function ‘sqrt’”

In the regarding c-file, l#241:
} else if ((u1 == 0.5) && (u0 >= 0.0)) {
y = sqrt(u0);
l#44: real_T look1_binlgpw( real_T u0 , const real_T bp0[], const real_T table[],
uint32_T maxIndex)

Is there any chance I can fix this by adding some files / headers?

Thx, Alex

It was a problem regarding the compiler / simulink. I isolated the S-Function, now I get loads of “undefined reference to nlp_in” errors.

#define S_FUNCTION_NAME   acados_solver_sfunction_ocp_model
#define S_FUNCTION_LEVEL  2

#define MDL_START

// acados
#include "print.h"
#include "math.h"
#include "sim_interface.h"
#include "external_function_interface.h"

// example specific
#include "ocp_model_model.h"
#include "acados_solver_ocp_model.h"

#include "simstruc.h"

//#define SAMPLINGTIME -1
#define SAMPLINGTIME 0.25

static void mdlInitializeSizes (SimStruct *S)
{
    // specify the number of continuous and discrete states
    ssSetNumContStates(S, 0);
    ssSetNumDiscStates(S, 0);

                  

    // specify the number of input ports
    if ( !ssSetNumInputPorts(S, 10) )
        return;

    // specify the number of output ports
    if ( !ssSetNumOutputPorts(S, 6) )
        return;

    // specify dimension information for the input ports
    // x0
    ssSetInputPortVectorDimension(S, 0, 3);
    // y_ref
    ssSetInputPortVectorDimension(S, 1, 30 * 6);
    // y_ref_e
    ssSetInputPortVectorDimension(S, 2, 3);
    // parameters
    ssSetInputPortVectorDimension(S, 3, (30+1) * 1);
    // lbx
    ssSetInputPortVectorDimension(S, 4, 3);
    // ubx
    ssSetInputPortVectorDimension(S, 5, 3);
    // lbu
    ssSetInputPortVectorDimension(S, 6, 3);
    // ubu
    ssSetInputPortVectorDimension(S, 7, 3);
    // lh
    ssSetInputPortVectorDimension(S, 8, 2);
    // uh
    ssSetInputPortVectorDimension(S, 9, 2);

    // specify dimension information for the output ports
    ssSetOutputPortVectorDimension(S, 0, 3 ); // optimal input
    ssSetOutputPortVectorDimension(S, 1, 1 ); // solver status
    ssSetOutputPortVectorDimension(S, 2, 1 ); // KKT residuals
    ssSetOutputPortVectorDimension(S, 3, 3 ); // first state
    ssSetOutputPortVectorDimension(S, 4, 1); // computation times
    ssSetOutputPortVectorDimension(S, 5, 1 ); // sqp iter

    // specify the direct feedthrough status
    // should be set to 1 for all inputs used in mdlOutputs
    ssSetInputPortDirectFeedThrough(S, 0, 1);
    ssSetInputPortDirectFeedThrough(S, 1, 1);
    ssSetInputPortDirectFeedThrough(S, 2, 1);
    ssSetInputPortDirectFeedThrough(S, 3, 1);
    ssSetInputPortDirectFeedThrough(S, 4, 1);
    ssSetInputPortDirectFeedThrough(S, 5, 1);
    ssSetInputPortDirectFeedThrough(S, 6, 1);
    ssSetInputPortDirectFeedThrough(S, 7, 1);
    ssSetInputPortDirectFeedThrough(S, 8, 1);
    ssSetInputPortDirectFeedThrough(S, 9, 1);

    // one sample time
    ssSetNumSampleTimes(S, 1);
}


#if defined(MATLAB_MEX_FILE)

#define MDL_SET_INPUT_PORT_DIMENSION_INFO
#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO

static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo)
{
    if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) )
         return;
}

static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo)
{
    if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) )
         return;
}

#endif /* MATLAB_MEX_FILE */


static void mdlInitializeSampleTimes(SimStruct *S)
{
    ssSetSampleTime(S, 0, SAMPLINGTIME);
    ssSetOffsetTime(S, 0, 0.0);
}


static void mdlStart(SimStruct *S)
{
    acados_create();
}

static void mdlOutputs(SimStruct *S, int_T tid)
{
    InputRealPtrsType in_sign;
    

    // local buffer
    real_t buffer[6];


    /* go through inputs */
    // initial condition
    in_sign = ssGetInputPortRealSignalPtrs(S, 0);
    for (int i = 0; i < 3; i++)
        buffer[i] = (double)(*in_sign[i]);
    ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", buffer);
    ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", buffer);


    // y_ref - stage-variant !!!
    in_sign = ssGetInputPortRealSignalPtrs(S, 1);

    for (int ii = 0; ii < 30; ii++)
    {
        for (int jj = 0; jj < 6; jj++)
            buffer[jj] = (double)(*in_sign[ii*6+jj]);
        ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "yref", (void *) buffer);
    }



    // y_ref_e
    in_sign = ssGetInputPortRealSignalPtrs(S, 2);

    for (int i = 0; i < 3; i++)
        buffer[i] = (double)(*in_sign[i]);

    ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 30, "yref", (void *) buffer);


    // parameters - stage-variant !!!
    in_sign = ssGetInputPortRealSignalPtrs(S, 3);

    // update value of parameters
    for (int ii = 0; ii <= 30; ii++) 
    {
        for (int jj = 0; jj < 1; jj++)
            buffer[jj] = (double)(*in_sign[ii*1+jj]);
        acados_update_params(ii, buffer, 1);
    }



    // lbx
    in_sign = ssGetInputPortRealSignalPtrs(S, 4);

    for (int i = 0; i < 3; i++)
        buffer[i] = (double)(*in_sign[i]);

    for (int ii = 1; ii < 30; ii++)
        ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lbx", buffer);

    // ubx
    in_sign = ssGetInputPortRealSignalPtrs(S, 5);

    for (int i = 0; i < 3; i++)
        buffer[i] = (double)(*in_sign[i]);

    for (int ii = 1; ii < 30; ii++)
        ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ubx", buffer);


    // lbu
    in_sign = ssGetInputPortRealSignalPtrs(S, 6);

    for (int i = 0; i < 3; i++)
        buffer[i] = (double)(*in_sign[i]);

    for (int ii = 0; ii < 30; ii++)
        ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lbu", buffer);

    // ubu
    in_sign = ssGetInputPortRealSignalPtrs(S, 7);

    for (int i = 0; i < 3; i++)
        buffer[i] = (double)(*in_sign[i]);

    for (int ii = 0; ii < 30; ii++)
        ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ubu", buffer);




    // lh
    in_sign = ssGetInputPortRealSignalPtrs(S, 8);

    for (int i = 0; i < 2; i++)
        buffer[i] = (double)(*in_sign[i]);

    for (int ii = 0; ii < 30; ii++)
        ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lh", buffer);

    // uh
    in_sign = ssGetInputPortRealSignalPtrs(S, 9);

    for (int i = 0; i < 2; i++)
        buffer[i] = (double)(*in_sign[i]);

    for (int ii = 0; ii < 30; ii++)
        ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "uh", buffer);

    /* call solver */
    int rti_phase = 0;
    ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "rti_phase", &rti_phase);
    int acados_status = acados_solve();


    /* set outputs */
    // assign pointers to output signals
    real_t *out_u0, *out_status, *out_sqp_iter, *out_KKT_res, *out_x1, *out_cpu_time;
    int tmp_int;

    out_u0          = ssGetOutputPortRealSignal(S, 0);
    out_status      = ssGetOutputPortRealSignal(S, 1);
    out_KKT_res     = ssGetOutputPortRealSignal(S, 2);
    out_x1          = ssGetOutputPortRealSignal(S, 3);
    out_cpu_time    = ssGetOutputPortRealSignal(S, 4);
    out_sqp_iter    = ssGetOutputPortRealSignal(S, 5);

    // extract solver info
    *out_status = (real_t) acados_status;
    *out_KKT_res = (real_t) nlp_out->inf_norm_res;
//    *out_cpu_time = (real_t) nlp_out->total_time;
    
    // get solution time
    ocp_nlp_get(nlp_config, nlp_solver, "time_tot", (void *) out_cpu_time);

    // get sqp iter
    ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", (void *) &tmp_int);
    *out_sqp_iter = (real_t) tmp_int;
//    *out_sqp_iter = (real_t) nlp_out->sqp_iter;

    // get solution
    ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "u", (void *) out_u0);

    // get next state
    ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 1, "x", (void *) out_x1);

}

static void mdlTerminate(SimStruct *S)
{
    acados_free();
}


#ifdef  MATLAB_MEX_FILE
#include "simulink.c"
#else
#include "cg_sfun.h"
#endif

Looks like a header is missing after acados code generation. Will keep you updated

I solved this by renaming the “acados/utils/math.h” file to math1.h. There was a weird conflict with the <math.h>. I dont know if this is logical, but it worked.