Public Member Functions | Static Public Attributes | Private Attributes | List of all members
uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence Class Reference
Inheritance diagram for uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence:
Inheritance graph
[legend]

Public Member Functions

def __init__ (self, turbulent_diffusion_coefficients, buoyancy_flux, stability_param, source_pos, n_points, start_time, max_particles_per_iter=10, max_life_time=-1)
 
def compute_plume_rise (self, t)
 
def create_particles (self, t)
 
def max_particles_per_iter (self)
 
def set_max_particles_per_iter (self, n_particles)
 
def set_plume_particles (self, t, x, y, z, time_creation)
 
def update (self, t=0.0)
 

Static Public Attributes

string LABEL = 'passive_scalar_turbulence'
 

Private Attributes

 _buoyancy_flux
 
 _dt
 
 _max_life_time
 
 _max_particles_per_iter
 
 _pnts
 
 _stability_param
 
 _t
 
 _time_creation
 
 _turbulent_diffusion_coefficients
 
 _vel_turbulent_diffusion
 

Detailed Description

Plume model implementation based on [1]. The chemical plume is described
here by discretized particles generated that are generated on the Cartesian
position given as the source of the plume. The plume is treated as a
passive scalar turbulence, meaning that it will not affect the
environmental fluid flow.

To model the dynamics of the plume particles, the Lagrangian particle
random walk approach [2] is used. The particles are generated from the
source position in batches at each iteration to ensure a steady flow and
each particle has its position $(x_k, y_k, z_k)$ at the instant
$t_k$ computed as

$$
    x_k = x_{k - 1} + (u_a + u_i) \Delta t
$$

$$
    y_k = y_{k - 1} + (v_a + v_i) \Delta t
$$

$$
    z_k = z_{k - 1} + (w_a + w_b + w_i) \Delta t
$$

where $(u_a, v_a, w_a)$ are the particle's velocities due to the
current velocity, $(u_t, v_t, w_t)$ are the particle's velocities
due to turbulent diffusion, and $w_b$ is the vertical buoyant
velocity.

!!! note "[1] `Tian and Zhang, 2010`"
    Yu Tian and Aiqun Zhang, "Simulation environment and guidance system
    for AUV tracing chemical plume in 3-dimensions," 2010 2nd International
    Asia Conference on Informatics in Control, Automation and Robotics
    (CAR 2010), Mar. 2010.

!!! note "[2] `Mestres et al., 2003`"
    M. Mestres et al., "Modelling of the Ebro River plume. Validation with
    field observations," Scientia Marina, vol. 67, no. 4, pp. 379-391,
    Dec. 2003.

Definition at line 21 of file passive_scalar_turbulence.py.

Constructor & Destructor Documentation

def uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.__init__ (   self,
  turbulent_diffusion_coefficients,
  buoyancy_flux,
  stability_param,
  source_pos,
  n_points,
  start_time,
  max_particles_per_iter = 10,
  max_life_time = -1 
)
Passive scalar turbulent plume model constructor.

> **Parameters**

* `turbulent_diffusion_coefficients` (*type:* `list`): a vector with 
three elements containing the turbulent diffusion coefficients 
for each degree of freedom of the particles ($x$, $y$ and $z$)
* `buoyancy_flux` (*type:* `float`): parameter used to compute the 
plume rise
* `stability_param` (*type:* `float`): parameter used to compute the 
plume rise
* `source_pos` (*type:* `list`): vector containing the Cartesian 
coordinates for the plume source (represented in the ENU inertial frame)
* `n_points` (*type:* `int`): maximum number of particles to be generated 
for the plume
* `start_time` (*type:* `float`): plume model creation time stamp
* `max_particles_per_iter` (*default:* 10, *type:* `int`): maximum 
number of particles to be generated per iteration
* `max_life_time` (*type:* `float`): maximum life time for each particle
from the time of creation in seconds

Definition at line 67 of file passive_scalar_turbulence.py.

Member Function Documentation

def uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.compute_plume_rise (   self,
  t 
)
The plume rise equation is used to compute the vertical buoyant
velocity. It is based on the experimental results presented in [1]
and can be written as

$H(u, s, t) = 2.6 ( F t^2 / u )^{1/3} (t^2 s + 4.3)^{-1/3}$

where $F$ is the buoyancy flux parameter and $s$ the
stability parameters, and both can be tuned by the user. $u$ is
the magnitude of the current velocity on the horizontal plane. The
resulting vertical buoyant velocity will be computed as follows

$w_b = H(u, s, t + \Delta t) - H(u, s, t) / \Delta t$

!!! note "[1] `Domenico, 1985`"
    Anfossi, Domenico. "Analysis of plume rise data from five TVA steam
    plants." Journal of climate and applied meteorology 24.11 (1985):
    1225-1236.

> **Parameters**

* `t` (*type:* `float`): current time stamp in seconds

> **Returns**

Plume rise velocity components vector.

Definition at line 214 of file passive_scalar_turbulence.py.

def uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.create_particles (   self,
  t 
)
Create random number of particles for one iteration up to the given
maximum limit and remove all particles that have left the plume's
bounding box limits.

> **Parameters**

* `t` (*type:* `float`): time stamp in seconds

Definition at line 140 of file passive_scalar_turbulence.py.

def uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.max_particles_per_iter (   self)
Return the maximum number of particles to be generated per iteration
from the source of the plume.

Definition at line 112 of file passive_scalar_turbulence.py.

def uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.set_max_particles_per_iter (   self,
  n_particles 
)
Set the maximum number of particles to be generated per iteration from
the source of the plume.

> **Parameters**

* `n_particles` (*type:* `int`): number of particles

> **Returns**

`True` if the new maximum number of particles could be set.
`False` if the input is equal or smaller than zero.

Definition at line 119 of file passive_scalar_turbulence.py.

def uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.set_plume_particles (   self,
  t,
  x,
  y,
  z,
  time_creation 
)
Load the plume particles' position vectors and time of creation.

> **Parameters**

* `t` (*type:* `float`): Current time stamp in seconds
* `x` (*type:* `list`): List of X coordinates
* `y` (*type:* `list`): List of Y coordinates
* `z` (*type:* `list`): List of Z coordinates
* `time_creation` (*type:* `list`): List of time stamps of creation
    of each particle

Definition at line 188 of file passive_scalar_turbulence.py.

def uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.update (   self,
  t = 0.0 
)
Update the position of all particles and create/remove particles from
the plume according to the bounding box limit constraints and the
maximum number of particles allowed.

> **Parameters**

* `t` (*type:* `float`): current time stamp in seconds

> **Returns**

`True` if update was succesful, `False` if computed time step is invalid.

Definition at line 251 of file passive_scalar_turbulence.py.

Member Data Documentation

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._buoyancy_flux
private

Definition at line 107 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._dt
private

Definition at line 265 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._max_life_time
private

Definition at line 103 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._max_particles_per_iter
private

Definition at line 102 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._pnts
private

Definition at line 100 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._stability_param
private

Definition at line 109 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._t
private

Definition at line 266 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._time_creation
private

Definition at line 163 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._turbulent_diffusion_coefficients
private

Definition at line 98 of file passive_scalar_turbulence.py.

uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence._vel_turbulent_diffusion
private

Definition at line 101 of file passive_scalar_turbulence.py.

string uuv_plume_model.passive_scalar_turbulence.PlumePassiveScalarTurbulence.LABEL = 'passive_scalar_turbulence'
static

Definition at line 63 of file passive_scalar_turbulence.py.


The documentation for this class was generated from the following file:


uuv_plume_simulator
Author(s): Musa Morena Marcusso Manhaes
autogenerated on Mon Jun 10 2019 15:41:28