From 03f3cd173f60fb2f45a762a3a194d14e6febe032 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Wed, 12 Oct 2022 12:04:23 +0100 Subject: [PATCH 1/2] 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 --- gz-waves/src/WaveSimulationSinusoid.cc | 142 ++++++++++++++++--------- gz-waves/src/WaveSimulation_TEST.cc | 89 +++++++++++----- 2 files changed, 154 insertions(+), 77 deletions(-) diff --git a/gz-waves/src/WaveSimulationSinusoid.cc b/gz-waves/src/WaveSimulationSinusoid.cc index 472cee19..40ac3d5f 100644 --- a/gz-waves/src/WaveSimulationSinusoid.cc +++ b/gz-waves/src/WaveSimulationSinusoid.cc @@ -22,10 +22,48 @@ namespace gz { namespace waves { + /// \todo Proposed changes + /// + /// 1. set wind velocity as magnitude v (m/s) and direction theta (rad). + /// + /// 2. set wave height H or amplitude A = H/2 + /// + /// 4. allow the dispersion relation to be configured - or set depth + /// /////////////////////////////////////////////////////////////////////////////// // WaveSimulationSinusoid::Impl + /// model description + /// + /// waves are defined on a Lx x Ly mesh with Nx x Ny samples + /// where Lx = Ly = L and Nx = Ny = N. + /// + /// H - wave height + /// A - wave amplitide = H/2 + /// T - wave period + /// w - wave angular frequency = 2 pi / T + /// k - wave number = w^2 / g for infinite depth + /// (x, y) - position + /// eta - wave height + /// + /// eta(x, y, t) = A cos(k (x cos(theta) + y sin(theta)) - w t) + /// + /// cd = cos(theta) - projection of wave direction on x-axis + /// sd = sin(theta) - projection of wave direction on y-axis + /// + /// a = k (x cd + y sd) - w t + /// sa = sin(a) + /// ca = cos(a) + /// + /// da/dx = k cd + /// da/dy = k sd + /// + /// h = eta(x, y, y) = A ca + /// dh/dx = - da/dx A sa + /// dh/dx = - da/dy A sa + /// + class WaveSimulationSinusoid::Impl { public: ~Impl(); @@ -74,15 +112,15 @@ namespace waves private: void ComputeCurrentAmplitudes(double _time); - private: int N; - private: int N2; - private: int NOver2; - private: double L; - private: double wave_angle; - private: double dir_x, dir_y; - private: double amplitude; - private: double period; - private: double time; + private: int N{2}; + private: int N2{2}; + private: int NOver2{1}; + private: double L{1.0}; + private: double wave_angle{0.0}; + private: double dir_x{1.0}, dir_y{0.0}; + private: double amplitude{1.0}; + private: double period{1.0}; + private: double time{0.0}; }; WaveSimulationSinusoid::Impl::~Impl() @@ -95,11 +133,7 @@ namespace waves N(_N), N2(_N * _N), NOver2(_N / 2), - L(_L), - wave_angle(0.0), - amplitude(2.5), - period(8.0), - time(0.0) + L(_L) { } @@ -112,6 +146,7 @@ namespace waves { this->dir_x = _dir_x; this->dir_y = _dir_y; + this->wave_angle = std::atan2(_dir_y, _dir_x); } void WaveSimulationSinusoid::Impl::SetAmplitude(double _amplitude) @@ -133,8 +168,11 @@ namespace waves std::vector& _heights) { // Derived wave properties - double omega = 2.0 * M_PI / this->period; - double k = Physics::DeepWaterDispersionToWavenumber(omega); + double w = 2.0 * M_PI / this->period; + double wt = w * this->time; + double k = Physics::DeepWaterDispersionToWavenumber(w); + double cd = std::cos(this->wave_angle); + double sd = std::sin(this->wave_angle); // Wave update double LOverN = this->L / this->N; @@ -142,7 +180,7 @@ namespace waves for (size_t iy=0; iyN; ++iy) { // Regular grid - double vy = iy * LOverN - LOver2; + double y = iy * LOverN - LOver2; for (size_t ix=0; ixN; ++ix) { @@ -150,12 +188,12 @@ namespace waves size_t idx = iy * this->N + ix; // Regular grid - double vx = ix * LOverN - LOver2; + double x = ix * LOverN - LOver2; // Single wave - double angle = k * vx - omega * time; - double c = std::cos(angle); - double h = this->amplitude * c; + double a = k * (x * cd + y * sd) - wt; + double ca = std::cos(a); + double h = this->amplitude * ca; _heights[idx] = h; } @@ -167,8 +205,11 @@ namespace waves std::vector& _dhdy) { // Derived wave properties - double omega = 2.0 * M_PI / this->period; - double k = Physics::DeepWaterDispersionToWavenumber(omega); + double w = 2.0 * M_PI / this->period; + double wt = w * this->time; + double k = Physics::DeepWaterDispersionToWavenumber(w); + double cd = std::cos(this->wave_angle); + double sd = std::sin(this->wave_angle); // Wave update double LOverN = this->L / this->N; @@ -176,7 +217,7 @@ namespace waves for (size_t iy=0; iyN; ++iy) { // Regular grid - double vy = iy * LOverN - LOver2; + double y = iy * LOverN - LOver2; for (size_t ix=0; ixN; ++ix) { @@ -184,16 +225,15 @@ namespace waves size_t idx = iy * this->N + ix; // Regular grid - double vx = ix * LOverN - LOver2; - double vy = iy * LOverN - LOver2; + double x = ix * LOverN - LOver2; // Single wave - double angle = k * vx - omega * time; - double dangle = k; - - double s = std::sin(angle); - double dhdx = - dangle * this->amplitude * s; - double dhdy = 0.0; + double a = k * (x * cd + y * sd) - wt; + double dadx = k * cd; + double dady = k * sd; + double sa = std::sin(a); + double dhdx = - dadx * this->amplitude * sa; + double dhdy = - dady * this->amplitude * sa; _dhdx[idx] = dhdx; _dhdy[idx] = dhdy; @@ -227,15 +267,18 @@ namespace waves std::vector& _dsxdy) { // Derived wave properties - double omega = 2.0 * M_PI / this->period; - double k = Physics::DeepWaterDispersionToWavenumber(omega); + double w = 2.0 * M_PI / this->period; + double wt = w * this->time; + double k = Physics::DeepWaterDispersionToWavenumber(w); + double cd = std::cos(this->wave_angle); + double sd = std::sin(this->wave_angle); // Wave update double LOverN = this->L / this->N; double LOver2 = this->L / 2.0; for (size_t iy=0; iyN; ++iy) { - // double vy = iy * LOverN - LOver2; + double y = iy * LOverN - LOver2; for (size_t ix=0; ixN; ++ix) { @@ -243,23 +286,23 @@ namespace waves size_t idx = iy * this->N + ix; // Regular grid - double vx = ix * LOverN - LOver2; + double x = ix * LOverN - LOver2; // Single wave - double angle = k * vx - omega * time; - double dangle = k; - double c = std::cos(angle); - double s = std::sin(angle); - double h = this->amplitude * c; - double dhdx = - dangle * this->amplitude * s; - double dhdy = 0.0; + double a = k * (x * cd + y * sd) - wt; + double dadx = k * cd; + double dady = k * sd; + double ca = std::cos(a); + double sa = std::sin(a); + double h = this->amplitude * ca; + double dhdx = - dadx * this->amplitude * sa; + double dhdy = - dady * this->amplitude * sa; _h[idx] = h; _dhdx[idx] = dhdx; _dhdy[idx] = dhdy; } } - } /////////////////////////////////////////////////////////////////////////////// @@ -304,21 +347,21 @@ namespace waves void WaveSimulationSinusoid::ComputeHeights( std::vector& _h) { - impl->ComputeHeights(_h); + impl->ComputeHeights(_h); } void WaveSimulationSinusoid::ComputeHeightDerivatives( std::vector& _dhdx, std::vector& _dhdy) { - impl->ComputeHeightDerivatives(_dhdx, _dhdy); + impl->ComputeHeightDerivatives(_dhdx, _dhdy); } void WaveSimulationSinusoid::ComputeDisplacements( std::vector& _sx, std::vector& _sy) { - impl->ComputeDisplacements(_sx, _sy); + impl->ComputeDisplacements(_sx, _sy); } void WaveSimulationSinusoid::ComputeDisplacementDerivatives( @@ -326,7 +369,7 @@ namespace waves std::vector& _dsydy, std::vector& _dsxdy) { - impl->ComputeDisplacementDerivatives(_dsxdx, _dsydy, _dsxdy); + impl->ComputeDisplacementDerivatives(_dsxdx, _dsydy, _dsxdy); } void WaveSimulationSinusoid::ComputeDisplacementsAndDerivatives( @@ -339,7 +382,8 @@ namespace waves std::vector& _dsydy, std::vector& _dsxdy) { - impl->ComputeDisplacementsAndDerivatives(_h, _dhdx, _dhdy, _sx, _sy, _dsxdx, _dsydy, _dsxdy); + impl->ComputeDisplacementsAndDerivatives( + _h, _dhdx, _dhdy, _sx, _sy, _dsxdx, _dsydy, _dsxdy); } } diff --git a/gz-waves/src/WaveSimulation_TEST.cc b/gz-waves/src/WaveSimulation_TEST.cc index 3c62c431..d6980766 100644 --- a/gz-waves/src/WaveSimulation_TEST.cc +++ b/gz-waves/src/WaveSimulation_TEST.cc @@ -121,37 +121,35 @@ class WaveSimulationSinusoidTestSuite : public ::testing::Test { protected: void SetUp() override - { - double time = 0.0; + { } void TearDown() override - { + { } - double time = 0.0; - // Grid dimensions - const int N = 4; - const int N2 = N*N; - const double L = 10.0; - const double dir_x = 1.0; - const double dir_y = 0.0; + const int N{8}; + const int N2{N*N}; + const double L{10.0}; // Parameters - const double amplitude = 1.0; - const double period = 10.0; + const double amplitude{2.0}; + const double period{10.0}; // Wave spectrum - const double omega = 2.0 * M_PI / period; - const double k = omega * omega / 9.8; + const double w{2.0 * M_PI / period}; + const double k{w * w / 9.8}; }; -TEST_F(WaveSimulationSinusoidTestSuite, testHeights) +TEST_F(WaveSimulationSinusoidTestSuite, TestHeightsDirX) { + double time = 5.0; + // Wave simulation - std::unique_ptr waveSim(new WaveSimulationSinusoid(N, L)); - waveSim->SetDirection(dir_x, dir_y); + std::unique_ptr waveSim( + new WaveSimulationSinusoid(N, L)); + waveSim->SetDirection(1.0, 0.0); waveSim->SetAmplitude(amplitude); waveSim->SetPeriod(period); waveSim->SetTime(time); @@ -166,25 +164,27 @@ TEST_F(WaveSimulationSinusoidTestSuite, testHeights) for (size_t iy=0, idx=0; iy waveSim(new WaveSimulationSinusoid(N, L)); - waveSim->SetDirection(dir_x, dir_y); + std::unique_ptr waveSim( + new WaveSimulationSinusoid(N, L)); + waveSim->SetDirection(2.0, -1.0); waveSim->SetAmplitude(amplitude); waveSim->SetPeriod(period); waveSim->SetTime(time); @@ -192,6 +192,39 @@ TEST_F(WaveSimulationSinusoidTestSuite, testDisplacements) // Grid spacing and offset double lm = - L / 2.0; double dl = L / N; + double wt = w * time; + double theta = std::atan2(-1.0, 2.0); + double cd = std::cos(theta); + double sd = std::sin(theta); + + // Verify heights + std::vector h(N2); + waveSim->ComputeHeights(h); + + for (size_t iy=0, idx=0; iy waveSim( + new WaveSimulationSinusoid(N, L)); + waveSim->SetDirection(1.0, 0.0); + waveSim->SetAmplitude(amplitude); + waveSim->SetPeriod(period); + waveSim->SetTime(5.0); // Verify displacements (expect zero for sinusoid waves) std::vector sx(N2); From 3713a7962270f013fe018595490d532373b1db2b Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Wed, 12 Oct 2022 12:09:15 +0100 Subject: [PATCH 2/2] Waves: rename monochromatic_waves model - Rename to regular waves. Signed-off-by: Rhys Mainwaring --- .../{monochromatic_waves => regular_waves}/model.config | 6 ++++-- .../{monochromatic_waves => regular_waves}/model.sdf | 2 +- 2 files changed, 5 insertions(+), 3 deletions(-) rename gz-waves-models/world_models/{monochromatic_waves => regular_waves}/model.config (63%) rename gz-waves-models/world_models/{monochromatic_waves => regular_waves}/model.sdf (98%) diff --git a/gz-waves-models/world_models/monochromatic_waves/model.config b/gz-waves-models/world_models/regular_waves/model.config similarity index 63% rename from gz-waves-models/world_models/monochromatic_waves/model.config rename to gz-waves-models/world_models/regular_waves/model.config index df9f7fd0..29064b6b 100644 --- a/gz-waves-models/world_models/monochromatic_waves/model.config +++ b/gz-waves-models/world_models/regular_waves/model.config @@ -1,7 +1,7 @@ - Monochromatic Waves + Regular Waves 1.0 model.sdf @@ -11,7 +11,9 @@ - Monochromatic surface waves. This model uses the materials from the `waves` + Regular surface waves. i.e. plane progressive waves of a single frequency. + + This model uses the materials from the `waves` model to prevent duplicating the large mesh files. diff --git a/gz-waves-models/world_models/monochromatic_waves/model.sdf b/gz-waves-models/world_models/regular_waves/model.sdf similarity index 98% rename from gz-waves-models/world_models/monochromatic_waves/model.sdf rename to gz-waves-models/world_models/regular_waves/model.sdf index 03547908..a888b473 100644 --- a/gz-waves-models/world_models/monochromatic_waves/model.sdf +++ b/gz-waves-models/world_models/regular_waves/model.sdf @@ -1,6 +1,6 @@ - + true