Skip to content

Commit b0f98ed

Browse files
committed
Waves: enable wave direction in the sinusoid wave model (#80)
* Waves: enable wave direction in the sinusoid wave model - Allow wave direction to be set for regular waves. - Add test for a wave direction not parallel to the x-axis Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com> * Waves: rename monochromatic_waves model - Rename to regular waves. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
1 parent b644d1a commit b0f98ed

File tree

4 files changed

+235
-77
lines changed

4 files changed

+235
-77
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
2+
<?xml version='1.0'?>
3+
<model>
4+
<name>Regular Waves</name>
5+
<version>1.0</version>
6+
<sdf version='1.6'>model.sdf</sdf>
7+
8+
<author>
9+
<name>Rhys Mainwaring</name>
10+
<email>rhys.mainwaring@me.com</email>
11+
</author>
12+
13+
<description>
14+
Regular surface waves. i.e. plane progressive waves of a single frequency.
15+
16+
This model uses the materials from the `waves`
17+
model to prevent duplicating the large mesh files.
18+
</description>
19+
</model>
20+
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
<?xml version='1.0' ?>
2+
<sdf version="1.6">
3+
<model name="regular_waves">
4+
<static>true</static>
5+
<plugin
6+
filename="gz-waves1-waves-model-system"
7+
name="gz::sim::systems::WavesModel">
8+
<static>0</static>
9+
<update_rate>30</update_rate>
10+
<wave>
11+
<algorithm>sinusoid</algorithm>
12+
<number>1</number>
13+
<amplitude>2.0</amplitude>
14+
<period>6.0</period>
15+
<direction>1 0</direction>
16+
</wave>
17+
</plugin>
18+
<link name="base_link">
19+
<visual name="visual">
20+
<geometry>
21+
<mesh>
22+
<uri>models://waves/materials/mesh_L256m_N256.dae</uri>
23+
</mesh>
24+
</geometry>
25+
<material>
26+
<ambient>0.0 0.05 0.8 0.92</ambient>
27+
<diffuse>0.0 0.1 0.7 0.92</diffuse>
28+
<specular>0.7 0.7 0.7 0.92</specular>
29+
<pbr>
30+
<metal>
31+
<albedo_map>models://waves/materials/water.jpg</albedo_map>
32+
<normal_map>models://waves/materials/wave_normals.dds</normal_map>
33+
<environment_map>models://waves/materials/skybox_lowres.dds</environment_map>
34+
<roughness>0.3</roughness>
35+
<metalness>0.1</metalness>
36+
</metal>
37+
</pbr>
38+
</material>
39+
<plugin
40+
filename="gz-waves1-waves-visual-system"
41+
name="gz::sim::systems::WavesVisual">
42+
<static>0</static>
43+
<mesh_deformation_method>DYNAMIC_GEOMETRY</mesh_deformation_method>
44+
<tiles_x>0 0</tiles_x>
45+
<tiles_y>0 0</tiles_y>
46+
<wave>
47+
<algorithm>sinusoid</algorithm>
48+
<number>1</number>
49+
<amplitude>2.0</amplitude>
50+
<period>6.0</period>
51+
<direction>1 0</direction>
52+
</wave>
53+
<shader language="metal">
54+
<vertex>models://waves/materials/waves_vs.metal</vertex>
55+
<fragment>models://waves/materials/waves_fs.metal</fragment>
56+
</shader>
57+
</plugin>
58+
</visual>
59+
</link>
60+
</model>
61+
</sdf>

gz-waves/src/WaveSimulationSinusoid.cc

+93-49
Original file line numberDiff line numberDiff line change
@@ -22,10 +22,48 @@ namespace gz
2222
{
2323
namespace waves
2424
{
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+
///
2533

2634
///////////////////////////////////////////////////////////////////////////////
2735
// WaveSimulationSinusoid::Impl
2836

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+
2967
class WaveSimulationSinusoid::Impl
3068
{
3169
public: ~Impl();
@@ -74,15 +112,15 @@ namespace waves
74112

75113
private: void ComputeCurrentAmplitudes(double _time);
76114

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};
86124
};
87125

88126
WaveSimulationSinusoid::Impl::~Impl()
@@ -95,11 +133,7 @@ namespace waves
95133
N(_N),
96134
N2(_N * _N),
97135
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)
103137
{
104138
}
105139

@@ -112,6 +146,7 @@ namespace waves
112146
{
113147
this->dir_x = _dir_x;
114148
this->dir_y = _dir_y;
149+
this->wave_angle = std::atan2(_dir_y, _dir_x);
115150
}
116151

117152
void WaveSimulationSinusoid::Impl::SetAmplitude(double _amplitude)
@@ -133,29 +168,32 @@ namespace waves
133168
std::vector<double>& _heights)
134169
{
135170
// 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);
138176

139177
// Wave update
140178
double LOverN = this->L / this->N;
141179
double LOver2 = this->L / 2.0;
142180
for (size_t iy=0; iy<this->N; ++iy)
143181
{
144182
// Regular grid
145-
double vy = iy * LOverN - LOver2;
183+
double y = iy * LOverN - LOver2;
146184

147185
for (size_t ix=0; ix<this->N; ++ix)
148186
{
149187
// Row major index
150188
size_t idx = iy * this->N + ix;
151189

152190
// Regular grid
153-
double vx = ix * LOverN - LOver2;
191+
double x = ix * LOverN - LOver2;
154192

155193
// 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;
159197

160198
_heights[idx] = h;
161199
}
@@ -167,33 +205,35 @@ namespace waves
167205
std::vector<double>& _dhdy)
168206
{
169207
// 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);
172213

173214
// Wave update
174215
double LOverN = this->L / this->N;
175216
double LOver2 = this->L / 2.0;
176217
for (size_t iy=0; iy<this->N; ++iy)
177218
{
178219
// Regular grid
179-
double vy = iy * LOverN - LOver2;
220+
double y = iy * LOverN - LOver2;
180221

181222
for (size_t ix=0; ix<this->N; ++ix)
182223
{
183224
// Row major index
184225
size_t idx = iy * this->N + ix;
185226

186227
// Regular grid
187-
double vx = ix * LOverN - LOver2;
188-
double vy = iy * LOverN - LOver2;
228+
double x = ix * LOverN - LOver2;
189229

190230
// 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;
197237

198238
_dhdx[idx] = dhdx;
199239
_dhdy[idx] = dhdy;
@@ -227,39 +267,42 @@ namespace waves
227267
std::vector<double>& _dsxdy)
228268
{
229269
// 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);
232275

233276
// Wave update
234277
double LOverN = this->L / this->N;
235278
double LOver2 = this->L / 2.0;
236279
for (size_t iy=0; iy<this->N; ++iy)
237280
{
238-
// double vy = iy * LOverN - LOver2;
281+
double y = iy * LOverN - LOver2;
239282

240283
for (size_t ix=0; ix<this->N; ++ix)
241284
{
242285
// Row major index
243286
size_t idx = iy * this->N + ix;
244287

245288
// Regular grid
246-
double vx = ix * LOverN - LOver2;
289+
double x = ix * LOverN - LOver2;
247290

248291
// 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;
256300

257301
_h[idx] = h;
258302
_dhdx[idx] = dhdx;
259303
_dhdy[idx] = dhdy;
260304
}
261305
}
262-
263306
}
264307

265308
///////////////////////////////////////////////////////////////////////////////
@@ -304,29 +347,29 @@ namespace waves
304347
void WaveSimulationSinusoid::ComputeHeights(
305348
std::vector<double>& _h)
306349
{
307-
impl->ComputeHeights(_h);
350+
impl->ComputeHeights(_h);
308351
}
309352

310353
void WaveSimulationSinusoid::ComputeHeightDerivatives(
311354
std::vector<double>& _dhdx,
312355
std::vector<double>& _dhdy)
313356
{
314-
impl->ComputeHeightDerivatives(_dhdx, _dhdy);
357+
impl->ComputeHeightDerivatives(_dhdx, _dhdy);
315358
}
316359

317360
void WaveSimulationSinusoid::ComputeDisplacements(
318361
std::vector<double>& _sx,
319362
std::vector<double>& _sy)
320363
{
321-
impl->ComputeDisplacements(_sx, _sy);
364+
impl->ComputeDisplacements(_sx, _sy);
322365
}
323366

324367
void WaveSimulationSinusoid::ComputeDisplacementDerivatives(
325368
std::vector<double>& _dsxdx,
326369
std::vector<double>& _dsydy,
327370
std::vector<double>& _dsxdy)
328371
{
329-
impl->ComputeDisplacementDerivatives(_dsxdx, _dsydy, _dsxdy);
372+
impl->ComputeDisplacementDerivatives(_dsxdx, _dsydy, _dsxdy);
330373
}
331374

332375
void WaveSimulationSinusoid::ComputeDisplacementsAndDerivatives(
@@ -339,7 +382,8 @@ namespace waves
339382
std::vector<double>& _dsydy,
340383
std::vector<double>& _dsxdy)
341384
{
342-
impl->ComputeDisplacementsAndDerivatives(_h, _dhdx, _dhdy, _sx, _sy, _dsxdx, _dsydy, _dsxdy);
385+
impl->ComputeDisplacementsAndDerivatives(
386+
_h, _dhdx, _dhdy, _sx, _sy, _dsxdx, _dsydy, _dsxdy);
343387
}
344388

345389
}

0 commit comments

Comments
 (0)