This project shows how Non-Linear Model Predictive Control can be used to achieve rotor-level control of a tilting quadrotor and compares it performances with state-of-the-art Feedback Linearization tecniques.
This project depends on two sub-projects:
- MATMPC, which provides the NMPC code.
- high-fidelity-tilting-quadrotor, which contains the high fidelity model for the tilting quadrotor.
The following steps are required only when the project is cloned for the first time or if the model parameters are changed (only model generation is required in this case).
The default SQP solver is hpipm_sparse
which requires to be installed and compiled to be used by Matlab.
-
Follow https://github.com/giaf/hpipm#getting-started to install BLASFEO and hpipm in your system.
-
Compile the interface for MATLAB running
compile_hpipm.m
. Eventually, please refer to https://github.com/sparcs-unipd/MATMPC/blob/master/doc/HPIPM-Tutorial.txt for detailed instructions.
The parameters (mass, inertia, thrust and torque coefficients, physical limits) of the tilting quadrotor and its default initial condition for the simulations are stored in highFidelityTiltingQuadrotorData.m. These paremeters must be provided to Model_Generation.m to generate the mex
function for the NMPC. To do so, run
Model_Generation('highFidelityTiltingQuadrotor','highFidelityTiltingQuadrotorData');
and confirm with y
when required. The first argument highFidelityTiltingQuadrotor specifies the (simplified) model equations, the structure of the cost fuction and the existence of state and input constraints.
The pre-computed planar
and 7 options are provided:
trajectory | ||
---|---|---|
1 | 2 m | 1 m |
2 | 3 m | 1.5 m |
3 | 4 m | 2 m |
4 | 5 m | 2.5 m |
5 | 6 m | 3 m |
6 | 7 m | 3.5 m |
7 | 8 m | 4 m |
It is also possible to generate or to provide custom trajectories.
The MATLAB live script highFidelityTiltingQuadrotorTrjGen.mlx provide easy trajectory generation with initial linear dynamics smoothing. The computed trajectory is then saved in custom_trajecotries/reference.mat
.
To run the accurate simulation with the NMPC controller use
NMPChighFidelityTiltingQuadrotor.slx
while to run the simualtion with a FL controller (please see here for detailed explanation) run
FLhighFidelityTiltingQuadrotor.slx
The controllers are tuned in initNMPChighFidelityTiltingQuadrotor.m and initFLhighFidelityTiltingQuadrotor.m, respectively.