Skip to content

Tim-Salzmann/l4casadi

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

71 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

PyPI version L4CasADi CI Downloads

*Due to a bug, Hessians for functions with non-scalar outputs were wrong prior to version 1.3.0


Learning 4 CasADi Framework

L4CasADi enables the seamless integration of PyTorch-learned models with CasADi for efficient and potentially hardware-accelerated numerical optimization. The only requirement on the PyTorch model is to be traceable and differentiable.

Collision-free minimum snap optimized trajectory through a NeRF Energy Efficient Fish Navigation in Turbulent Flow
Open In Colab                                                Open In Colab                      

Two L4CasADi examples: Collision-free trajectory through a NeRF and Navigation in Turbulent Flow

arXiv: Learning for CasADi: Data-driven Models in Numerical Optimization

Talk: Youtube

Table of Content

If you use this framework please cite the following two paper

@article{salzmann2023neural,
  title={Real-time Neural-MPC: Deep Learning Model Predictive Control for Quadrotors and Agile Robotic Platforms},
  author={Salzmann, Tim and Kaufmann, Elia and Arrizabalaga, Jon and Pavone, Marco and Scaramuzza, Davide and Ryll, Markus},
  journal={IEEE Robotics and Automation Letters},
  doi={10.1109/LRA.2023.3246839},
  year={2023}
}
@inproceedings{{salzmann2024l4casadi,
  title={Learning for CasADi: Data-driven Models in Numerical Optimization},
  author={Salzmann, Tim and Arrizabalaga, Jon and Andersson, Joel and Pavone, Marco and Ryll, Markus},
  booktitle={Learning for Dynamics and Control Conference (L4DC)},
  year={2024}
}

Projects using L4CasADi

  • Real-time Neural-MPC: Deep Learning Model Predictive Control for Quadrotors and Agile Robotic Platforms
    Paper | Code
  • Neural Potential Field for Obstacle-Aware Local Motion Planning
    Paper | Video | Code
  • N-MPC for Deep Neural Network-Based Collision Avoidance exploiting Depth Images
    Paper | Code

If your project is using L4CasADi and you would like to be featured here, please reach out.


Installation

Prerequisites

Independently if you install from source or via pip you will need to meet the following requirements:

  • Working build system: CMake compatible C++ compiler.
  • PyTorch (>=2.0) installation in your python environment.
    python -c "import torch; print(torch.__version__)"

Pip Install (CPU Only)

  • Ensure Torch CPU-version is installed
    pip install torch>=2.0 --index-url https://download.pytorch.org/whl/cpu
  • Ensure all build dependencies are installed
setuptools>=68.1
scikit-build>=0.17
cmake>=3.27
ninja>=1.11
  • Run
    pip install l4casadi --no-build-isolation

From Source (CPU Only)

  • Clone the repository
    git clone https://github.com/Tim-Salzmann/l4casadi.git

  • All build dependencies installed via
    pip install -r requirements_build.txt

  • Build from source
    pip install . --no-build-isolation

The --no-build-isolation flag is required for L4CasADi to find and link against the installed PyTorch.

GPU (CUDA)

CUDA installation requires nvcc to be installed which is part of the CUDA toolkit and can be installed on Linux via sudo apt-get -y install cuda-toolkit-XX-X (where XX-X is your installed Cuda version - e.g. 12-3). Once the CUDA toolkit is installed nvcc is commonly found at /usr/local/cuda/bin/nvcc.

Make sure nvcc -V can be executed and run pip install l4casadi --no-build-isolation or CUDACXX=<PATH_TO_NVCC> pip install . --no-build-isolation to build from source.

If nvcc is not automatically part of your path you can specify the nvcc path for L4CasADi. E.g. CUDACXX=<PATH_TO_NVCC> pip install l4casadi --no-build-isolation.


Online Learning and Updating

L4CasADi supports updating the PyTorch model online in the CasADi graph. To use this feature, pass mutable=True when initializing a L4CasADi. To update the model, call the update function on the L4CasADi object. You can optionally pass an updated model as parameter. If no model is passed, the reference passed at initialization is assumed to be updated and will be used for the update.


Naive L4CasADi

While L4CasADi was designed with efficiency in mind by internally leveraging torch's C++ interface, this can still result in overhead, which can be disproportionate for small, simple models. Thus, L4CasADi additionally provides a NaiveL4CasADiModule which directly recreates the PyTorch computational graph using CasADi operations and copies the weights --- leading to a pure C computational graph without context switches to torch. However, this approach is limited to a small predefined subset of PyTorch operations --- only MultiLayerPerceptron models and CPU inference are supported.

The torch framework overhead dominates for networks smaller than three hidden layers, each with 64 neurons (or equivalent). For models smaller than this size we recommend using the NaiveL4CasADiModule. For larger models, the overhead becomes negligible and L4CasADi should be used.

naive_mlp = l4c.naive.MultiLayerPerceptron(2, 128, 1, 2, 'Tanh')
l4c_model = l4c.L4CasADi(naive_mlp, model_expects_batch_dim=True)
x_sym = cs.MX.sym('x', 2, 1)
y_sym = l4c_model(x_sym)


Real-time L4CasADi

Real-time L4Casadi (former Approximated approach in ML-CasADi) is the underlying framework powering Real-time Neural-MPC. It replaces complex models with local Taylor approximations. For certain optimization procedures (such as MPC with multiple shooting nodes) this can lead to improved optimization times. However, Real-time L4Casadi, comes with many restrictions (only Python, no C(++) code generation, ...) and is therefore not a one-to-one replacement for L4Casadi. Rather it is a complementary framework for certain special use cases.

More information here.

l4c_model = l4c.RealTimeL4CasADi(pyTorch_model, approximation_order=1) # approximation_order=2
x_sym = cs.MX.sym('x', 2, 1)
y_sym = l4c_model(x_sym)
casadi_func = cs.Function('model_rt_approx',
[x_sym, l4c_model.get_sym_params()],
[y_sym])
x = np.ones([1, size_in]) # torch needs batch dimension
casadi_param = l4c_model.get_params(x)
casadi_out = casadi_func(x.transpose((-2, -1)), casadi_param) # transpose for vector rep. expected by casadi


Examples

l4c_model = l4c.L4CasADi(pyTorch_model, model_expects_batch_dim=True, device='cpu') # device='cuda' for GPU
x_sym = cs.MX.sym('x', 2, 1)
y_sym = l4c_model(x_sym)
f = cs.Function('y', [x_sym], [y_sym])
df = cs.Function('dy', [x_sym], [cs.jacobian(y_sym, x_sym)])
ddf = cs.Function('ddy', [x_sym], [cs.hessian(y_sym, x_sym)[0]])
x = cs.DM([[0.], [2.]])
print(l4c_model(x))
print(f(x))
print(df(x))
print(ddf(x))

Please note that only casadi.MX symbolic variables are supported as input.

Multi-input multi-output functions can be realized by concatenating the symbolic inputs when passing to the model and splitting them inside the PyTorch function.

To use GPU (CUDA) simply pass device="cuda" to the L4CasADi constructor.

Further examples:


Acados Integration

To use this framework with Acados:

An example of how a PyTorch model can be used as dynamics model in the Acados framework for Model Predictive Control can be found in examples/acados.py

To use L4CasADi with Acados you will have to set model_external_shared_lib_dir and model_external_shared_lib_name in the AcadosOcp.solver_options accordingly.

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

l4casadi/examples/acados.py

Lines 156 to 160 in 421de6e

ocp.solver_options.model_external_shared_lib_dir = self.external_shared_lib_dir
if COST == 'LINEAR_LS':
ocp.solver_options.model_external_shared_lib_name = self.external_shared_lib_name
else:
ocp.solver_options.model_external_shared_lib_name = self.external_shared_lib_name + ' -l' + l4c_y_expr.name


FYIs

Batch Dimension

If your PyTorch model expects a batch dimension as first dimension (which most models do) you should pass model_expects_batch_dim=True to the L4CasADi constructor. The MX input to the L4CasADi component is then expected to be a vector of shape [X, 1]. L4CasADi will add a batch dimension of 1 automatically such that the input to the underlying PyTorch model is of shape [1, X].


Warm Up

Note that PyTorch builds the graph on first execution. Thus, the first call(s) to the CasADi function will be slow. You can warm up to the execution graph by calling the generated CasADi function one or multiple times before using it.