15 from __future__
import print_function
16 from plume
import Plume
17 from copy
import deepcopy
23 Plume model implementation based on [1]. The chemical plume is described 24 here by discretized particles generated that are generated on the Cartesian 25 position given as the source of the plume. The plume is treated as a 26 passive scalar turbulence, meaning that it will not affect the 27 environmental fluid flow. 29 To model the dynamics of the plume particles, the Lagrangian particle 30 random walk approach [2] is used. The particles are generated from the 31 source position in batches at each iteration to ensure a steady flow and 32 each particle has its position $(x_k, y_k, z_k)$ at the instant 36 x_k = x_{k - 1} + (u_a + u_i) \Delta t 40 y_k = y_{k - 1} + (v_a + v_i) \Delta t 44 z_k = z_{k - 1} + (w_a + w_b + w_i) \Delta t 47 where $(u_a, v_a, w_a)$ are the particle's velocities due to the 48 current velocity, $(u_t, v_t, w_t)$ are the particle's velocities 49 due to turbulent diffusion, and $w_b$ is the vertical buoyant 52 !!! note "[1] `Tian and Zhang, 2010`" 53 Yu Tian and Aiqun Zhang, "Simulation environment and guidance system 54 for AUV tracing chemical plume in 3-dimensions," 2010 2nd International 55 Asia Conference on Informatics in Control, Automation and Robotics 56 (CAR 2010), Mar. 2010. 58 !!! note "[2] `Mestres et al., 2003`" 59 M. Mestres et al., "Modelling of the Ebro River plume. Validation with 60 field observations," Scientia Marina, vol. 67, no. 4, pp. 379-391, 63 LABEL =
'passive_scalar_turbulence' 65 def __init__(self, turbulent_diffusion_coefficients, buoyancy_flux,
66 stability_param, source_pos, n_points, start_time,
67 max_particles_per_iter=10, max_life_time=-1):
69 Passive scalar turbulent plume model constructor. 73 * `turbulent_diffusion_coefficients` (*type:* `list`): a vector with 74 three elements containing the turbulent diffusion coefficients 75 for each degree of freedom of the particles ($x$, $y$ and $z$) 76 * `buoyancy_flux` (*type:* `float`): parameter used to compute the 78 * `stability_param` (*type:* `float`): parameter used to compute the 80 * `source_pos` (*type:* `list`): vector containing the Cartesian 81 coordinates for the plume source (represented in the ENU inertial frame) 82 * `n_points` (*type:* `int`): maximum number of particles to be generated 84 * `start_time` (*type:* `float`): plume model creation time stamp 85 * `max_particles_per_iter` (*default:* 10, *type:* `int`): maximum 86 number of particles to be generated per iteration 87 * `max_life_time` (*type:* `float`): maximum life time for each particle 88 from the time of creation in seconds 90 Plume.__init__(self, source_pos, n_points, start_time)
92 assert len(turbulent_diffusion_coefficients) == 3,
'There should be ' \
93 'three elements in the turbulent diffusion coefficients vector' 95 assert buoyancy_flux >= 0,
'Buoyancy flux coefficient must be equal ' \
96 'or greater than zero' 114 Return the maximum number of particles to be generated per iteration 115 from the source of the plume. 121 Set the maximum number of particles to be generated per iteration from 122 the source of the plume. 126 * `n_particles` (*type:* `int`): number of particles 130 `True` if the new maximum number of particles could be set. 131 `False` if the input is equal or smaller than zero. 137 print(
'Number of particles per iteration must be greater than zero')
142 Create random number of particles for one iteration up to the given 143 maximum limit and remove all particles that have left the plume's 148 * `t` (*type:* `float`): time stamp in seconds 152 if self.
_pnts is not None:
155 p_filter = self.get_contraints_filter()
158 if np.sum(p_filter) > 0:
160 self.
_pnts = self.
_pnts[np.nonzero(p_filter)[0], :]
166 if self._pnts.shape[0] + n_particles > self._n_points:
167 n_particles = self._n_points - self._pnts.shape[0]
169 if self._pnts.shape[0] == self._n_points:
172 new_pnts = np.vstack(
173 (self._source_pos[0] * np.ones(n_particles),
174 self._source_pos[1] * np.ones(n_particles),
175 self._source_pos[2] * np.ones(n_particles))).T
177 if self.
_pnts is None:
178 self.
_pnts = new_pnts
182 self.
_pnts = np.vstack((self.
_pnts, new_pnts))
190 Load the plume particles' position vectors and time of creation. 194 * `t` (*type:* `float`): Current time stamp in seconds 195 * `x` (*type:* `list`): List of X coordinates 196 * `y` (*type:* `list`): List of Y coordinates 197 * `z` (*type:* `list`): List of Z coordinates 198 * `time_creation` (*type:* `list`): List of time stamps of creation 201 self.
_pnts = np.zeros(shape=(len(x), 3))
208 self.
_pnts[:, 0] = np.array(x)
209 self.
_pnts[:, 1] = np.array(y)
210 self.
_pnts[:, 2] = np.array(z)
216 The plume rise equation is used to compute the vertical buoyant 217 velocity. It is based on the experimental results presented in [1] 218 and can be written as 220 $H(u, s, t) = 2.6 ( F t^2 / u )^{1/3} (t^2 s + 4.3)^{-1/3}$ 222 where $F$ is the buoyancy flux parameter and $s$ the 223 stability parameters, and both can be tuned by the user. $u$ is 224 the magnitude of the current velocity on the horizontal plane. The 225 resulting vertical buoyant velocity will be computed as follows 227 $w_b = H(u, s, t + \Delta t) - H(u, s, t) / \Delta t$ 229 !!! note "[1] `Domenico, 1985`" 230 Anfossi, Domenico. "Analysis of plume rise data from five TVA steam 231 plants." Journal of climate and applied meteorology 24.11 (1985): 236 * `t` (*type:* `float`): current time stamp in seconds 240 Plume rise velocity components vector. 242 horz_vel = np.sqrt(self._current_vel[0]**2 + self._current_vel[1]**2)
247 return 2.6 * np.multiply(
252 """Update the position of all particles and create/remove particles from 253 the plume according to the bounding box limit constraints and the 254 maximum number of particles allowed. 258 * `t` (*type:* `float`): current time stamp in seconds 262 `True` if update was succesful, `False` if computed time step is invalid. 264 t -= self._start_time
268 print(
'Time step must be greater than zero')
276 2 * (0.5 - np.random.rand(
277 self._vel_turbulent_diffusion.shape[0])) * \
283 self.
_pnts[:, i] += self._current_vel[i] * self.
_dt 286 self.
_pnts[:, i] += \
289 self.
_pnts[np.nonzero(self.
_pnts[:, 2].flatten() >= 0)[0], i] = 0.0
def create_particles(self, t)
def max_particles_per_iter(self)
_turbulent_diffusion_coefficients
def compute_plume_rise(self, t)
def set_plume_particles(self, t, x, y, z, time_creation)
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 set_max_particles_per_iter(self, n_particles)