passive_scalar_turbulence.py
Go to the documentation of this file.
1 # Copyright (c) 2016 The UUV Simulator Authors.
2 # All rights reserved.
3 #
4 # Licensed under the Apache License, Version 2.0 (the "License");
5 # you may not use this file except in compliance with the License.
6 # You may obtain a copy of the License at
7 #
8 # http://www.apache.org/licenses/LICENSE-2.0
9 #
10 # Unless required by applicable law or agreed to in writing, software
11 # distributed under the License is distributed on an "AS IS" BASIS,
12 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 # See the License for the specific language governing permissions and
14 # limitations under the License.
15 from __future__ import print_function
16 from plume import Plume
17 from copy import deepcopy
18 import numpy as np
19 
20 
22  """
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.
28 
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
33  $t_k$ computed as
34 
35  $$
36  x_k = x_{k - 1} + (u_a + u_i) \Delta t
37  $$
38 
39  $$
40  y_k = y_{k - 1} + (v_a + v_i) \Delta t
41  $$
42 
43  $$
44  z_k = z_{k - 1} + (w_a + w_b + w_i) \Delta t
45  $$
46 
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
50  velocity.
51 
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.
57 
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,
61  Dec. 2003.
62  """
63  LABEL = 'passive_scalar_turbulence'
64 
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):
68  """
69  Passive scalar turbulent plume model constructor.
70 
71  > **Parameters**
72 
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
77  plume rise
78  * `stability_param` (*type:* `float`): parameter used to compute the
79  plume rise
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
83  for the plume
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
89  """
90  Plume.__init__(self, source_pos, n_points, start_time)
91 
92  assert len(turbulent_diffusion_coefficients) == 3, 'There should be ' \
93  'three elements in the turbulent diffusion coefficients vector'
94 
95  assert buoyancy_flux >= 0, 'Buoyancy flux coefficient must be equal ' \
96  'or greater than zero'
97 
98  self._turbulent_diffusion_coefficients = turbulent_diffusion_coefficients
99 
100  self._pnts = None
102  self._max_particles_per_iter = max(1, max_particles_per_iter)
103  self._max_life_time = max_life_time
104 
105  self.create_particles(0)
106 
107  self._buoyancy_flux = buoyancy_flux
108 
109  self._stability_param = stability_param
110 
111  @property
113  """
114  Return the maximum number of particles to be generated per iteration
115  from the source of the plume.
116  """
117  return self._max_particles_per_iter
118 
119  def set_max_particles_per_iter(self, n_particles):
120  """
121  Set the maximum number of particles to be generated per iteration from
122  the source of the plume.
123 
124  > **Parameters**
125 
126  * `n_particles` (*type:* `int`): number of particles
127 
128  > **Returns**
129 
130  `True` if the new maximum number of particles could be set.
131  `False` if the input is equal or smaller than zero.
132  """
133  if n_particles > 0:
134  self._max_particles_per_iter = n_particles
135  return True
136  else:
137  print('Number of particles per iteration must be greater than zero')
138  return False
139 
140  def create_particles(self, t):
141  """
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
144  bounding box limits.
145 
146  > **Parameters**
147 
148  * `t` (*type:* `float`): time stamp in seconds
149  """
150  n_particles = int(self._max_particles_per_iter * np.random.rand())
151 
152  if self._pnts is not None:
153 
154  # Remove the particles that are outside of the limits
155  p_filter = self.get_contraints_filter()
156  if self._max_life_time > 0:
157  p_filter = np.logical_and(p_filter, t - self._time_creation < self._max_life_time)
158  if np.sum(p_filter) > 0:
159  # Filter out the points outside of the limit box
160  self._pnts = self._pnts[np.nonzero(p_filter)[0], :]
161  self._vel_turbulent_diffusion = \
162  self._vel_turbulent_diffusion[np.nonzero(p_filter)[0], :]
163  self._time_creation = \
164  self._time_creation[np.nonzero(p_filter)[0]]
165 
166  if self._pnts.shape[0] + n_particles > self._n_points:
167  n_particles = self._n_points - self._pnts.shape[0]
168 
169  if self._pnts.shape[0] == self._n_points:
170  return
171 
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
176 
177  if self._pnts is None:
178  self._pnts = new_pnts
179  self._vel_turbulent_diffusion = np.zeros(new_pnts.shape)
180  self._time_creation = self._t * np.ones(new_pnts.shape[0])
181  else:
182  self._pnts = np.vstack((self._pnts, new_pnts))
183  self._vel_turbulent_diffusion = np.vstack(
184  (self._vel_turbulent_diffusion, np.zeros(new_pnts.shape)))
185  self._time_creation = np.hstack(
186  (self._time_creation, self._t * np.ones(new_pnts.shape[0])))
187 
188  def set_plume_particles(self, t, x, y, z, time_creation):
189  """
190  Load the plume particles' position vectors and time of creation.
191 
192  > **Parameters**
193 
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
199  of each particle
200  """
201  self._pnts = np.zeros(shape=(len(x), 3))
202  self._time_creation = np.zeros(len(time_creation))
203 
204  self._time_creation = np.array(time_creation)
205  self._time_creation -= np.max(time_creation)
206  self._time_creation += t
207 
208  self._pnts[:, 0] = np.array(x)
209  self._pnts[:, 1] = np.array(y)
210  self._pnts[:, 2] = np.array(z)
211 
212  self._vel_turbulent_diffusion = np.zeros(self._pnts.shape)
213 
214  def compute_plume_rise(self, t):
215  """
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
219 
220  $H(u, s, t) = 2.6 ( F t^2 / u )^{1/3} (t^2 s + 4.3)^{-1/3}$
221 
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
226 
227  $w_b = H(u, s, t + \Delta t) - H(u, s, t) / \Delta t$
228 
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):
232  1225-1236.
233 
234  > **Parameters**
235 
236  * `t` (*type:* `float`): current time stamp in seconds
237 
238  > **Returns**
239 
240  Plume rise velocity components vector.
241  """
242  horz_vel = np.sqrt(self._current_vel[0]**2 + self._current_vel[1]**2)
243 
244  if horz_vel == 0:
245  return 0.0
246  t2 = np.power(t - self._time_creation, 2)
247  return 2.6 * np.multiply(
248  np.power(self._buoyancy_flux * t2 / horz_vel, 1. / 3),
249  np.power(t2 * self._stability_param + 4.3, -1. / 3))
250 
251  def update(self, t=0.0):
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.
255 
256  > **Parameters**
257 
258  * `t` (*type:* `float`): current time stamp in seconds
259 
260  > **Returns**
261 
262  `True` if update was succesful, `False` if computed time step is invalid.
263  """
264  t -= self._start_time
265  self._dt = t - self._t
266  self._t = t
267  if self._dt <= 0.0:
268  print('Time step must be greater than zero')
269  return False
270 
271  self.create_particles(t)
272  # Update turbulent diffusion velocity component
273  for i in range(3):
274  # Calculate particle velocity due to turbulent diffusion
275  self._vel_turbulent_diffusion[:, i] = \
276  2 * (0.5 - np.random.rand(
277  self._vel_turbulent_diffusion.shape[0])) * \
278  np.sqrt(
279  6 * self._turbulent_diffusion_coefficients[i] / self._dt)
280  self._pnts[:, i] += self._vel_turbulent_diffusion[:, i] * self._dt
281 
282  # Add the current velocity component
283  self._pnts[:, i] += self._current_vel[i] * self._dt
284 
285  if i == 2:
286  self._pnts[:, i] += \
287  (self.compute_plume_rise(self._t + self._dt) -
288  self.compute_plume_rise(self._t))
289  self._pnts[np.nonzero(self._pnts[:, 2].flatten() >= 0)[0], i] = 0.0
290 
291  return True
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)


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