@@ -22,10 +22,48 @@ namespace gz
22
22
{
23
23
namespace waves
24
24
{
25
+ // / \todo Proposed changes
26
+ // /
27
+ // / 1. set wind velocity as magnitude v (m/s) and direction theta (rad).
28
+ // /
29
+ // / 2. set wave height H or amplitude A = H/2
30
+ // /
31
+ // / 4. allow the dispersion relation to be configured - or set depth
32
+ // /
25
33
26
34
// /////////////////////////////////////////////////////////////////////////////
27
35
// WaveSimulationSinusoid::Impl
28
36
37
+ // / model description
38
+ // /
39
+ // / waves are defined on a Lx x Ly mesh with Nx x Ny samples
40
+ // / where Lx = Ly = L and Nx = Ny = N.
41
+ // /
42
+ // / H - wave height
43
+ // / A - wave amplitide = H/2
44
+ // / T - wave period
45
+ // / w - wave angular frequency = 2 pi / T
46
+ // / k - wave number = w^2 / g for infinite depth
47
+ // / (x, y) - position
48
+ // / eta - wave height
49
+ // /
50
+ // / eta(x, y, t) = A cos(k (x cos(theta) + y sin(theta)) - w t)
51
+ // /
52
+ // / cd = cos(theta) - projection of wave direction on x-axis
53
+ // / sd = sin(theta) - projection of wave direction on y-axis
54
+ // /
55
+ // / a = k (x cd + y sd) - w t
56
+ // / sa = sin(a)
57
+ // / ca = cos(a)
58
+ // /
59
+ // / da/dx = k cd
60
+ // / da/dy = k sd
61
+ // /
62
+ // / h = eta(x, y, y) = A ca
63
+ // / dh/dx = - da/dx A sa
64
+ // / dh/dx = - da/dy A sa
65
+ // /
66
+
29
67
class WaveSimulationSinusoid ::Impl
30
68
{
31
69
public: ~Impl ();
@@ -74,15 +112,15 @@ namespace waves
74
112
75
113
private: void ComputeCurrentAmplitudes (double _time);
76
114
77
- private: int N;
78
- private: int N2;
79
- private: int NOver2;
80
- private: double L;
81
- private: double wave_angle;
82
- private: double dir_x, dir_y;
83
- private: double amplitude;
84
- private: double period;
85
- private: double time;
115
+ private: int N{ 2 } ;
116
+ private: int N2{ 2 } ;
117
+ private: int NOver2{ 1 } ;
118
+ private: double L{ 1.0 } ;
119
+ private: double wave_angle{ 0.0 } ;
120
+ private: double dir_x{ 1.0 } , dir_y{ 0.0 } ;
121
+ private: double amplitude{ 1.0 } ;
122
+ private: double period{ 1.0 } ;
123
+ private: double time{ 0.0 } ;
86
124
};
87
125
88
126
WaveSimulationSinusoid::Impl::~Impl ()
@@ -95,11 +133,7 @@ namespace waves
95
133
N (_N),
96
134
N2 (_N * _N),
97
135
NOver2 (_N / 2 ),
98
- L (_L),
99
- wave_angle (0.0 ),
100
- amplitude (2.5 ),
101
- period (8.0 ),
102
- time (0.0 )
136
+ L (_L)
103
137
{
104
138
}
105
139
@@ -112,6 +146,7 @@ namespace waves
112
146
{
113
147
this ->dir_x = _dir_x;
114
148
this ->dir_y = _dir_y;
149
+ this ->wave_angle = std::atan2 (_dir_y, _dir_x);
115
150
}
116
151
117
152
void WaveSimulationSinusoid::Impl::SetAmplitude (double _amplitude)
@@ -133,29 +168,32 @@ namespace waves
133
168
std::vector<double >& _heights)
134
169
{
135
170
// Derived wave properties
136
- double omega = 2.0 * M_PI / this ->period ;
137
- double k = Physics::DeepWaterDispersionToWavenumber (omega);
171
+ double w = 2.0 * M_PI / this ->period ;
172
+ double wt = w * this ->time ;
173
+ double k = Physics::DeepWaterDispersionToWavenumber (w);
174
+ double cd = std::cos (this ->wave_angle );
175
+ double sd = std::sin (this ->wave_angle );
138
176
139
177
// Wave update
140
178
double LOverN = this ->L / this ->N ;
141
179
double LOver2 = this ->L / 2.0 ;
142
180
for (size_t iy=0 ; iy<this ->N ; ++iy)
143
181
{
144
182
// Regular grid
145
- double vy = iy * LOverN - LOver2;
183
+ double y = iy * LOverN - LOver2;
146
184
147
185
for (size_t ix=0 ; ix<this ->N ; ++ix)
148
186
{
149
187
// Row major index
150
188
size_t idx = iy * this ->N + ix;
151
189
152
190
// Regular grid
153
- double vx = ix * LOverN - LOver2;
191
+ double x = ix * LOverN - LOver2;
154
192
155
193
// Single wave
156
- double angle = k * vx - omega * time ;
157
- double c = std::cos (angle );
158
- double h = this ->amplitude * c ;
194
+ double a = k * (x * cd + y * sd) - wt ;
195
+ double ca = std::cos (a );
196
+ double h = this ->amplitude * ca ;
159
197
160
198
_heights[idx] = h;
161
199
}
@@ -167,33 +205,35 @@ namespace waves
167
205
std::vector<double >& _dhdy)
168
206
{
169
207
// Derived wave properties
170
- double omega = 2.0 * M_PI / this ->period ;
171
- double k = Physics::DeepWaterDispersionToWavenumber (omega);
208
+ double w = 2.0 * M_PI / this ->period ;
209
+ double wt = w * this ->time ;
210
+ double k = Physics::DeepWaterDispersionToWavenumber (w);
211
+ double cd = std::cos (this ->wave_angle );
212
+ double sd = std::sin (this ->wave_angle );
172
213
173
214
// Wave update
174
215
double LOverN = this ->L / this ->N ;
175
216
double LOver2 = this ->L / 2.0 ;
176
217
for (size_t iy=0 ; iy<this ->N ; ++iy)
177
218
{
178
219
// Regular grid
179
- double vy = iy * LOverN - LOver2;
220
+ double y = iy * LOverN - LOver2;
180
221
181
222
for (size_t ix=0 ; ix<this ->N ; ++ix)
182
223
{
183
224
// Row major index
184
225
size_t idx = iy * this ->N + ix;
185
226
186
227
// Regular grid
187
- double vx = ix * LOverN - LOver2;
188
- double vy = iy * LOverN - LOver2;
228
+ double x = ix * LOverN - LOver2;
189
229
190
230
// Single wave
191
- double angle = k * vx - omega * time ;
192
- double dangle = k;
193
-
194
- double s = std::sin (angle );
195
- double dhdx = - dangle * this ->amplitude * s ;
196
- double dhdy = 0.0 ;
231
+ double a = k * (x * cd + y * sd) - wt ;
232
+ double dadx = k * cd ;
233
+ double dady = k * sd;
234
+ double sa = std::sin (a );
235
+ double dhdx = - dadx * this ->amplitude * sa ;
236
+ double dhdy = - dady * this -> amplitude * sa ;
197
237
198
238
_dhdx[idx] = dhdx;
199
239
_dhdy[idx] = dhdy;
@@ -227,39 +267,42 @@ namespace waves
227
267
std::vector<double >& _dsxdy)
228
268
{
229
269
// Derived wave properties
230
- double omega = 2.0 * M_PI / this ->period ;
231
- double k = Physics::DeepWaterDispersionToWavenumber (omega);
270
+ double w = 2.0 * M_PI / this ->period ;
271
+ double wt = w * this ->time ;
272
+ double k = Physics::DeepWaterDispersionToWavenumber (w);
273
+ double cd = std::cos (this ->wave_angle );
274
+ double sd = std::sin (this ->wave_angle );
232
275
233
276
// Wave update
234
277
double LOverN = this ->L / this ->N ;
235
278
double LOver2 = this ->L / 2.0 ;
236
279
for (size_t iy=0 ; iy<this ->N ; ++iy)
237
280
{
238
- // double vy = iy * LOverN - LOver2;
281
+ double y = iy * LOverN - LOver2;
239
282
240
283
for (size_t ix=0 ; ix<this ->N ; ++ix)
241
284
{
242
285
// Row major index
243
286
size_t idx = iy * this ->N + ix;
244
287
245
288
// Regular grid
246
- double vx = ix * LOverN - LOver2;
289
+ double x = ix * LOverN - LOver2;
247
290
248
291
// Single wave
249
- double angle = k * vx - omega * time ;
250
- double dangle = k;
251
- double c = std::cos (angle);
252
- double s = std::sin (angle);
253
- double h = this ->amplitude * c;
254
- double dhdx = - dangle * this ->amplitude * s;
255
- double dhdy = 0.0 ;
292
+ double a = k * (x * cd + y * sd) - wt;
293
+ double dadx = k * cd;
294
+ double dady = k * sd;
295
+ double ca = std::cos (a);
296
+ double sa = std::sin (a);
297
+ double h = this ->amplitude * ca;
298
+ double dhdx = - dadx * this ->amplitude * sa;
299
+ double dhdy = - dady * this ->amplitude * sa;
256
300
257
301
_h[idx] = h;
258
302
_dhdx[idx] = dhdx;
259
303
_dhdy[idx] = dhdy;
260
304
}
261
305
}
262
-
263
306
}
264
307
265
308
// /////////////////////////////////////////////////////////////////////////////
@@ -304,29 +347,29 @@ namespace waves
304
347
void WaveSimulationSinusoid::ComputeHeights (
305
348
std::vector<double >& _h)
306
349
{
307
- impl->ComputeHeights (_h);
350
+ impl->ComputeHeights (_h);
308
351
}
309
352
310
353
void WaveSimulationSinusoid::ComputeHeightDerivatives (
311
354
std::vector<double >& _dhdx,
312
355
std::vector<double >& _dhdy)
313
356
{
314
- impl->ComputeHeightDerivatives (_dhdx, _dhdy);
357
+ impl->ComputeHeightDerivatives (_dhdx, _dhdy);
315
358
}
316
359
317
360
void WaveSimulationSinusoid::ComputeDisplacements (
318
361
std::vector<double >& _sx,
319
362
std::vector<double >& _sy)
320
363
{
321
- impl->ComputeDisplacements (_sx, _sy);
364
+ impl->ComputeDisplacements (_sx, _sy);
322
365
}
323
366
324
367
void WaveSimulationSinusoid::ComputeDisplacementDerivatives (
325
368
std::vector<double >& _dsxdx,
326
369
std::vector<double >& _dsydy,
327
370
std::vector<double >& _dsxdy)
328
371
{
329
- impl->ComputeDisplacementDerivatives (_dsxdx, _dsydy, _dsxdy);
372
+ impl->ComputeDisplacementDerivatives (_dsxdx, _dsydy, _dsxdy);
330
373
}
331
374
332
375
void WaveSimulationSinusoid::ComputeDisplacementsAndDerivatives (
@@ -339,7 +382,8 @@ namespace waves
339
382
std::vector<double >& _dsydy,
340
383
std::vector<double >& _dsxdy)
341
384
{
342
- impl->ComputeDisplacementsAndDerivatives (_h, _dhdx, _dhdy, _sx, _sy, _dsxdx, _dsydy, _dsxdy);
385
+ impl->ComputeDisplacementsAndDerivatives (
386
+ _h, _dhdx, _dhdy, _sx, _sy, _dsxdx, _dsydy, _dsxdy);
343
387
}
344
388
345
389
}
0 commit comments