This repo contains a model predictive controller based on the single rigid body model and written in Python. It cames in two flavours: gradient-based via acados or sampling-based via jax. The controller is tested on real robots and is compatible with Mujoco.
Features gradient-based mpc:
- less than 5ms computation on an intel i7-13700H cpu
- optional integrators for model mismatch
- optional smoothing for the ground reaction forces
- optional foothold optimization
- optional real-time iteration or advanced-step real-time iteration
- optional zero moment point/center of mass constraints
Features sampling-based mpc:
- 10000 parallel rollouts in less than 2ms on an nvidia 4050 mobile gpu!
- optional step frequency adaptation for enhancing robustness
- implements different strategies: random sampling, mppi, or cemppi
- different control parametrizations: zero-order, linear splines or cubic splines (see mujoco-mpc)
Experiments with Aliengo | ||
---|---|---|
Simulations with Go2 | ||
Gradient-based MPC: It uses CasADI to define the model and acados to solve the optimal control problem. Sampling-based MPC: jax for both. The simulation environment is based on Mujoco.
-
install miniforge (x86_64)
-
create an environment using the file in the folder installation choosing between nvidia and integrated gpu, either with or without ros (to run the simulation, you don't need ros!):
conda env create -f mamba_environment.yml
-
clone the other submodules:
git submodule update --init --recursive
-
activate the conda environment
conda activate quadruped_pympc_env
-
go inside the folder acados and compile it pressing:
mkdir build cd build cmake .. make install -j4 pip install -e ./../interfaces/acados_template
-
inside the file .bashrc, given your path_to_acados, put:
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:"/path_to_acados/lib" export ACADOS_SOURCE_DIR="/path_to_acados"
Notice that if you are using Mac, you should set
DYLD_LIBRARY_PATH=$LD_LIBRARY_PATH:"/path_to_acados/lib" export ACADOS_SOURCE_DIR="/path_to_acados"
The first time you run the simulation with acados, in the terminal you will be asked to install tera_render. You should accept to proceed.
-
go inside the folder gym-quadruped and install it:
pip install -e .
-
activate the conda environment
conda activate quadruped_pympc_env
-
go in the folder simulation and press
python3 simulation_mujoco.py
In the file config.py, you can set up the robot, the mpc type (gradient, sampling..), its proprierties (real time iteration, sampling type, foothold optimization..), and other simulation params (reference, gait type..).
- you can interact with the simulation with your mouse to add disturbances, or with the keyboard by pressing
arrow up, arrow down -> add positive or negative forward velocity
arrow left, arrow right -> add positive or negative yaw velocity
ctrl -> set zero all velocities
If you find the work useful, please consider citing our work:
@INPROCEEDINGS{turrisi2024sampling,
title={On the Benefits of GPU Sample-Based Stochastic Predictive Controllers for Legged Locomotion},
author={Turrisi, Giulio and Modugno, Valerio and Amatucci, Lorenzo and Kanoulas, Dimitrios and Semini, Claudio},
booktitle={2024 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
year={2024}
}
This repository is maintained by Giulio Turrisi and Daniel Ordonez.