Is it possible to formulate OCP with a neural model for cost function?

Good day!
I am working on OCP for solving MPC problem. I would like to replace the casadi formulation of cost-function by an already trained neural network (model has 3 hidden layer with 300 neurons). Is it possible? If there is any hint for implementing this it will be appreciated.

1 Like

Dear Muhammad,

Have a look at this repo: GitHub - TUM-AAS/ml-casadi: Use PyTorch Models with CasADi and Acados

Or you can write a neural network using CasADi and load the trained neuron parameters, then follow every standard procedure of using acados. This might take some time, but I think it’s doable.

I’ve done something similar before, but I would say sometimes it’s unrealistic to expect the OCP solver to deal with such highly non-linear and non-convex problems.

I guess you can give a try to see how well it work. I suggest to allow multiple SQP iterations and enable line search with merit function. If the results are not satisfactory, maybe try to simplify the neural network with fewer layers and smaller width.

Sampling based method like Model Predictive Path Integral (MPPI) might also be an option.

Best,
Fenglong

Dear Fenglong! Thank for reply and interesting suggestions.

Hi,

I am the author of the referenced ml-casadi package. I recently re-worked the package and would suggest using the new package to anyone coming by this thread: GitHub - Tim-Salzmann/l4casadi: Use PyTorch Models with CasADi and Acados

It enables to use arbitrary PyTorch models (as long as they are traceable by TorchScript) in CasADI graphs including code generation and integration with acados (see examples).

Let me know if you have questions.

2 Likes

Hi @Tim! Thank you for reply. Actually, I have tested ml_casadi for Pytorch MLP model and it works very well. However I have question related to implementing ml_casadi with Acados. In ml_casadi, Pytorch model is linearized at given point before using it as casadi function in Acados solver. This leads that value of casadi function equals to output of the model only at points near to linearizing one. However I need to pass casadi function to Acados solver so the casadi function gives the same results of Pytorch model everywhere the input point is. Could you suggest how I can do it using l4_casadi/ml_casadi? I should mention that the Pytorch model that I am implementing represents potential filed function and not the dynamic of the robot as in your paper Real-time Neural-MPC.

Thanks in advance.

Hi @Muhammad,

because of these exact shortcomings of ml-casadi I started working on L4CasADi. L4CasADi should support exactly what you describe (if the PyTorch model can be traced). L4CasADi is not used and tested as thoroughly as ml-casadi, so there might be some hickups on the way. Let me know if you need help.

There is an acados example with L4CasADi in examples/casadi.py which should get you started.

Best
Tim

Hi @Tim,
I have tested L4Casadi for MLP (with 3 layers, 300 neurons) and It is working as it is needed no matter where the input is. Thank you. However, according to my experience in Acados, I 've seen it needs Casadi function to be expanded (such as formula 1 for example) But L4Casadi gives function in form such as y:(i0[3])->(o0) MXFunction . How can we get the expanded formulation of Casadi function from L4Casadi?

formula 1:
@1=43.2846, @2=3.33819, @3=4, @4=1.02491, @5=2.5, @6=0.279467, [(@1+(((@2*(x-@3))+(@4*(y-@5)))+(@6*theta))), (@1+(((@2*(x-@3))+(@4*(y-@5)))+(@6*theta))), (@1+(((@2*(x-@3))+(@4*(y-@5)))+(@6*theta))), (@1+(((@2*(x-@3))+(@4*(y-@5)))+(@6*theta))), (@1+(((@2*(x-@3))+...
Best,
Muhammad

Can you elaborate why and when this expanded formulation is needed?

CasADi rightfully treats the PyTorch module as external blackbox and won’t be able to symbollically expand the PyTorch operations.

An example of using L4CasADi with acados can be found in examples/acados.py

In Acados when it is needed to formulate cost function in the parameter cost_y_expr , the formulation which cost_y_expr accepts, is of type symbols of Casadi (as in expended formulation above). In file examples/acados.py Casadi function is used as model. Actually, I need to use the Casadi function for Pytorch model in the cost function i.e. for cost_y_expr. I have used file example/readme.py to describe my problem. I hope that @FreyJo corrects me if there is any misunderstanding with Acados.

Best,
Muhammad

P.S.
1- for example cost function for model with state vector sym_x and control input sym_u is given as
model.cost_y_expr = vertcat(sym_x, sym_u, custom_cost) where custom_cost is custom cost function and it should be in expanded formulation as formulation 1.

2- In ml-casadi I could expand result Casadi function but after linearization.

Hi Muhammad,

I updated the Acados example to include a (trivial indexing) cost_y_expr PyTorch function.

Let me know if this helps.

Hi Tim, sorry for late reply. Thank for updating. However, I have used expression l4c.L4CasADi for cost_y_expr but still have no matching in types. Here my implementation

    l4c_model = l4c.L4CasADi(model_loaded, has_batch=True)

    model.cost_y_expr = l4c_model

and what i have gotten

 File "/home/vladislav/acados/interfaces/acados_template/acados_template/acados_ocp_solver.py", line 132, in make_ocp_dims_consistent
    if is_empty(model.cost_y_expr_0) and ny_0 != 0:
  File "/home/vladislav/acados/interfaces/acados_template/acados_template/utils.py", line 133, in is_empty
    raise Exception("is_empty expects one of the following types: casadi.MX, casadi.SX, "
Exception: is_empty expects one of the following types: casadi.MX, casadi.SX, None, numpy array empty list, set. Got: <class 'l4casadi.l4casadi.L4CasADi'>

Hi Muhammad,

You are passing the class reference to model.cost_y_expr. However, the model.cost_y_expr expects a symbolic expression. You need to call the L4CasADi module with a symbolic input model.cost_y_expr = l4c_model(x) to get the required symbolic output.

You can see this procedure in the provided example

Hope this helps!

Hi Tim, Actually I have tested example/acados.py. It works as expected but when adding another state as here model.cost_expr = vertcat(x , l4c_y_expr(x)). or model.cost_expr = vertcat(x[0] , l4c_y_expr(x)) there was an error about not matching type or number even I tired to set them right. In addition, I have tried to set the following (where the model I have accepts 3 inputs) but also there were some issue.

l4c_model = l4c.L4CasADi(model_loaded, has_batch=True)
model.cost_y_expr = l4c_model(vertcat(x,y,z))

Sorry because I can’t now give you accurate details about the problem. On Monday I can send you more accurate details. Thanks a lot.

Hi Muhammad,

I suspect that model.cost_expr expects ac scalar, whereas you assign a symbolic vector vertcat(x , l4c_y_expr(x)).

l4c_model(vertcat(x,y,z)) should work if your model_loadedexpects the same input shape as your vertcatmatrix. As you specified has_batch = True (model expects a batch dimension) you have to make sure that the input is a vector of size vertcat(x,y,z).shape = (X, 1) where Xis the shape model_loaded expects for its input. L4Casadi will add the needed batch dimension internally.

Hi Tim, Thank you for replay. I will try to formulate issues here.
First, the Pytorch model that I have accepts 3 inputs (x,y,theta) and following there is the neural model:

class ONF(nn.Module):
    def __init__(self):
        super().__init__()
        self.mlp = nn.Sequential(*[
            nn.Linear(100, 100),
            nn.ReLU(),
            nn.Linear(100, 100),
            nn.ReLU(),
            nn.Linear(100, 100),
            nn.ReLU(),
            nn.Linear(100, 1),
            nn.ReLU()
        ])
        
        self.encoding_layer = nn.Linear(3, 100, bias=False)

    def forward(self, x):
        x = self.encoding_layer(x)
        x = torch.sin_(x)
        x = self.mlp(x)
        return x

In following there is my implementation in which I have tested the loaded_model with a tensor which size (3 , 1) and it gives an output, but when I passed a casadi vector with the same size to model gotten from L4Casadi there is an error about dimension.

    # State
    x = SX.sym('x') 
    y = SX.sym('y')   
    v = SX.sym('v')  
    theta = SX.sym('theta') 

    sym_x = vertcat(x, y, v ,theta)

    model_loaded = ONF()

    model_loaded.load_state_dict(torch.load('model.pth'))

    X_test = torch.tensor([1.4,2.5,0] , dtype=torch.float32)

    print(model_loaded(X_test))

    l4c_model = l4c.L4CasADi(model_loaded, has_batch=False, name='ext_cost')

    # l4c_model = l4c.L4CasADi(model_loaded, has_batch=True, name='ext_cost')

    sym = vertcat(x, y,theta)

    print(l4c_model(sym))

The output here is:

tensor([43.1518], grad_fn=<ReluBackward0>)
Traceback (most recent call last):
  File "/home/vladislav/l4casadi/examples/my_example.py", line 61, in <module>
    cost_model()
  File "/home/vladislav/l4casadi/examples/my_example.py", line 59, in cost_model
    print(l4c_model(sym))
 <Path to Error>
 <Path to Error>
 <Path to Error>
  File "/home/vladislav/.local/lib/python3.9/site-packages/torch/nn/modules/linear.py", line 114, in forward
    return F.linear(input, self.weight, self.bias)
RuntimeError: mat1 and mat2 shapes cannot be multiplied (3x1 and 3x100)

Also, I set has_batch=True , but the error was .../casadi/core/function_internal.cpp:2009: 'eval_sx' not defined for External

Finally, my goal is to set the L4CasADi model and the state and control vector of Acados model in cost_y_expr as following
model.cost_y_expr = vertcat(sym_x, sym_u , l4c_model(vertcat(x,y,theta)))
I don’t know if I have misunderstanding in implementation or using L4CasADi.

Best,
Muhammad

Hi Muhammad,

please use MX vs SX as symbolic SX does not support external module evaluation within casadi. Also your network expects a batch dimension. Therefore you have to set has_batch=True.

Working example:

class ONF(nn.Module):
    def __init__(self):
        super().__init__()
        self.mlp = nn.Sequential(*[
            nn.Linear(100, 100),
            nn.ReLU(),
            nn.Linear(100, 100),
            nn.ReLU(),
            nn.Linear(100, 100),
            nn.ReLU(),
            nn.Linear(100, 1),
            nn.ReLU()
        ])

        self.encoding_layer = nn.Linear(3, 100, bias=False)

    def forward(self, x):
        x = self.encoding_layer(x)
        x = torch.sin_(x)
        x = self.mlp(x)
        return x

# State
x = MX.sym('x')
y = MX.sym('y')
v = MX.sym('v')
theta = MX.sym('theta')

sym_x = vertcat(x, y, v ,theta)

model_loaded = ONF()

X_test = torch.tensor([1.4,2.5,0] , dtype=torch.float32)

print(model_loaded(X_test))

l4c_model = l4c.L4CasADi(model_loaded, has_batch=True, name='ext_cost')

sym = vertcat(x, y,theta)

print(l4c_model(DM(X_test.numpy())))
print(l4c_model(sym))
print(l4c_model(sym).shape)

Edit:
Your model does actually work without a explicit batch dimension. However, this is not the expected default behaviour of PyTorch modules: Why do some inputs need an axis for batch size but some don't? - PyTorch Forums

Therefore I decided to explicitly pass this information to L4CasADI if a batch dimension should be added during inference.

Thank you Tim. It fixed this issue. You are right, I have tested again with has_batch=False and the model didn’t work. However on the last stage of formulating Acados solver acados_solver = AcadosOcpSolver(ocp, json_file="acados_solver.json") , it gives undefined symbol: jac_ext_cost in shared lib <dir>/c_generated_code/libacados_ocp_solver_robot_model.so. When deleting the name from l4c_model, the error becomes jac_jac_l4casadi_f. Thanks anyway.

Hi Muhammad,

did you link the L4CasADi auto-generated lib into the acados code generation as per example in

in your example it should be something like

ocp.solver_options.model_external_shared_lib_dir = l4c_model.shared_lib_dir
ocp.solver_options.model_external_shared_lib_name = l4c_model.name

Thank you very much Tim, It has fixed my issue, However I will read example/acados.py more carefully to formulate my example because there are some concepts that I didn’t used in Acados before and it is used in your example such as cs.types.SimpleNamespace() . I think this is critical in your library.

All Best,
Muhammad

Actually I think

model_external_shared_lib_dir
model_external_shared_lib_name

should be the only specifics for combining L4CasADi with Acados. If you do find any more specifics, please let me know. I’ll add them to the README

Thanks
Tim