Welcome to the wiki of the uuv
project!
Here you can find up-to-date information on the uuv
repository.
First of all, the repository contains software that is used to simulate and control a single unmanned underwater vehicle (UUV) in the Matlab/Simulink environment.
The code is not fully functional yet. At the moment, the following items have been implemented:
- Directory in recommended Matlab/Simulink project format;
- UUV 6DOF dynamics block in Simulink (C S-function), including added mass, damping, hydrostatic and centripetal (deactivated for the time being) forces and external current effects;
- A thrust block in Simulink (C S-function) that takes propeller revolutions as input and returns the 6DOF thrust vector;
- A simple PID controller in surge, heave and yaw;
- A very basic line of sight guidance system;
- Very basic trajectory generation and following functions;
- Plotting and animation functions (Matlab);
- Preprocessing functions (Matlab), including data from the Minerva ROV used at NTNU.
Before the software can be considered as fully functional, the following items are required:
- Path planning methods in Matlab;
- Guidance methods (target & trajectory tracking and path following) in Simulink/Matlab for both ROVs and AUVs;
- ROV and AUV control routines (dynamic positioning and path controller) in Simulink;
- Thrust models for AUVs.
The code follows a standard Matlab/Simulink project convention. The main files and directories are as follows:
startup.m
: file that modifies the Matlab path so that all files and directories of interest can be accessed;cleanup.m
: file that clears unwanted clutter and cleans the Matlab path;.\data
: directory that contains the required parameters for the desired UUVs. Note that the data should be saved in.mat
format as a structure with the same format as the examplerov.mat
file..\functions
: directory that contains some useful functions;animateAUV.m
: post-processing, low-cost function used to animate the UUV in 3D space in Matlab;plotForces.m
: post-processing function used to plot the forces of interest in Matlab;plotMotions.m
: post-processing function use to plot the motions of interest in Matlab;plotPath.m
: post-processing function to plot the path of the UUV in Matlab;rotation.m
: function to rotate a 3D body in space in an inertial reference frame;skew.m
: function to create a skew-symmetric matrix.
.\models
: directory that contains the Simulink models of the UUVs;rov_thrust.c
: C function of the thrust dynamics of a ROV;rovSim_los.slx
: Simulink model of a ROV with line of sight guidance and PID control;uuv_dynamics.c
: C function of the 6DOF dynamics of the UUV;uuvSim_simple
: Simulink model of a simple UUV without thrust block.
.\scripts
: directory that contains the main scripts for running the simulations;rovSimRun.m
: function that runs the simulation for the ROV with line of sight guidance and PID control;rovSimSetup.m
: set-up function for the ROV;uuvSimRun.m
: function to run a simple UUV model;uuvSimRun_los.m
: function to run a UUV model with line of sight guidanceuuvSimSetup.m
: set-up function for an AUV.
Additionally, the following files and directories may also be of use:
.\docs
: directory that contains all documents, such as this one;.\extra
: directory that contains extra files;rovSim_trj.slx
: Simulink model of a ROV with minimum-snap trajectory generation and path following;test_trajectory.m
: file to test the generation of minimum-snap trajectories in 3D space;Trajectory.m
: class used to generate 3D trajectories (incomplete);uuvSimRun_trj.m
: file to run the simulation of a ROV that follows minimum-snap trajectories in 3D space (incomplete).
.\preprocessing
: directory that contains pre-processing functions;readData.m
: function used to read input data from UUV parameters and generate a structure compatible with the models used in this project.
.\work
: directory that contains all work and temporary files, which will be cleared at the end.
IMPORTANT: please, do NOT make changes to the master branch without approval. Pull down a personal branch and make changes and saves there instead.
The first step to complete before running the simulations is to compile the C-coded S-functions in Simulink (rov_thrust.c
and uuv_dynamics.c
) located in the .\models\
directory.
This can be done with the commands
mex rov_thrust.c
,
mex uuv_dynamics.c
.
As a result, you should see .mex
or .mexw64
in the directory .\models\
.
Note that before you take this step, it is fundamental to have a C/C++ compiler installed (supported by/compatible with Matlab).
- In Windows, install the MinGW-w64 compiler from the
Add-Ons
app. - In Linux, install gcc (which should be preinstalled).
- In OSX, install Xcode.
After the C files are compiled, it is possible to run the desired simulations.
From the main project directory, first run
startup
on the Matlab shell.
Then, you can run any simulations. As an example, run
uuvSimRun
.
When finished, run
cleanup
to clean up the temporary files and the Matlab path.
The Minerva ROV is in use at NTNU and well documented in the literature (especially in M.Sc. and Ph.D. theses from NTNU).
More information on the ROV can be found here https://www.ntnu.edu/oceans/minerva.
The dynamics coefficients and fits are taken from Mo (2015).
S. M. Mo (2015). Development of a Simulation Platform for ROV Systems. Norwegian University of Science and Technology (NTNU), M.Sc. thesis.
The notation and equations introduced in Fossen (2011) have been used to program the UUV dynamics. However, the downward right-hand rule convention (north,west,down) is employed at the moment.
Let us define the motions in 6 degrees of freedom (DOF) in the inertial reference frame as
and the 6DOF velocity vector in the body-fixed reference frame as
Additionally, it is possible to include the effects of an external current represented by the velocity vector
$$\mathbf{\nu}\mathrm{r} = \mathbf{\nu} - \mathbf{\nu}\mathrm{c} . $$
Then, the dynamics of an UUV can be expressed by the following system of ordinary differential equations:
$$\begin{bmatrix} \mathbf{\dot{\eta}} \ \mathbf{\dot{\nu}} \end{bmatrix} = \begin{bmatrix} \mathbf{J}(\mathbf{\eta}) \mathbf{\nu}\mathrm{r} \ \left( \mathbf{M}\mathrm{RB} + \mathbf{M}\mathrm{A} \right)^{-1} \left( - \mathbf{f}\mathrm{h} - \mathbf{f}\mathrm{d} - \mathbf{f}\mathrm{c} + \mathbf{f}_\mathrm{e} + \mathbf{\tau} \right) \end{bmatrix} ,$$
where
The restoring force vector is given by
where
The damping force vector is represented by a linear and a quadratic term:
$$ \mathbf{f}\mathrm{d} = \mathbf{D}\mathrm{l} \mathbf{\nu}\mathrm{r} + \mathbf{D}\mathrm{q} \mathrm{diag}\left( | \mathbf{\nu}\mathrm{r} |\right) \mathbf{\nu}\mathrm{r} , $$
where $$\mathbf{D}\mathrm{l}$$ and $$\mathbf{D}\mathrm{q}$$ are the linear and quadratic damping matrices, respectively.
The Coriolis and centripetal force vector is computed as follows:
$$ \mathbf{f}\mathrm{c} = \mathbf{C}\mathrm{RB}(\mathbf{\nu})\mathbf{\nu} + \mathbf{C}\mathrm{A}(\mathbf{\nu}\mathrm{r})\mathbf{\nu}_\mathrm{r} $$
where the first term represents a fictitious force that causes a movement of the UUV relative to the rotating reference frame due to the Earth's rotation and the second term describes the effects related to the added mass. Note that at the moment, this term is commented out.
The
where
The thrust force vector is calculated as
$$ \mathbf{f}\mathrm{th} = \rho \mathbf{D}^4 \odot \mathrm{K}\mathrm{T} \odot | \mathbf{n} | \odot \mathbf{n} \odot \mathbf{\theta} $$
where all vectors have the length equal to the number of propulsors and
$$ \mathbf{J}\mathrm{a} = \frac{\mathbf{\nu}\mathrm{a}}{\mathbf{n}\mathbf{D}}, $$
where
At the moment, only a basic line-of-sight (LOS) guidance system is implemented. A number
The desired heading angle is computed as
where
where $$ \alpha_k = \arctan \left( \frac{y_{k+1}-y_k}{x_{k+1}-x_k} \right) $$, with
At the moment, the desired depth is simply set based on the depth of the waypoints as
However, not that this is valid mainly for ROVs, with AUVs requiring a setting for the pitch angle as well.
At the moment, very simple PID controllers have been implemented for the control of the surge velocity,
The thrust force vector is computed from the inverse of the thrust allocation matrix as follows:
$$ \mathbf{f}\mathrm{th} = \mathbf{T}^{-1} \mathbf{p}\mathrm{c} , $$
where
$$ \mathbf{p}\mathrm{c} = \begin{bmatrix} p\mathrm{c,speed} & 0 & p_\mathrm{c,depth} & 0 & 0 & p_\mathrm{c,heading} \end{bmatrix}^T. $$
Using simple PID controllers, it is possible to obtain the control parameters for speed, depth and heading as
where
The desired heading
Path generation and tracking routines are still missing, although a simple minimum-snap trajectory generation and following scheme is implemented for ROVs.
F. Dukan (2014). ROV Motion Control Systems. Norwegian University of Science and Technology (NTNU), Ph.D. thesis.
T. I. Fossen (2011). Handbook of Marine Craft Hydrodynamics and Motion Control. John Wiley & Sons, first edition.
A. M. Lekkas (2014). Guidance and Path-Planning Systems for Autonomous Vehicles. Norwegian University of Science and Technology (NTNU), Ph.D. thesis.
S. M. Mo (2015). Development of a Simulation Platform for ROV Systems. Norwegian University of Science and Technology (NTNU), M.Sc. thesis.
- Path planning and tracking tools will need to be created.
- The convention used may be subject to change later on, although care must be taken not to get confused. Note that the animation displays the UUV in a NEU inertial frame.
- At the moment, transformation matrix relies on the roll, pitch and yaw angles. However, quaternions can be used in the future to prevent instabilities for angles close to
$$90^\circ$$ . - At the moment, the analysed UUVs are assumed not to travel far (in towing tanks or lakes). Hence, the Coriolis force correction has not been implemented yet. This will need to be done.
- At the moment, the tether force for ROVs is not included within the model.