Skip to content

Commit

Permalink
Merge 441b348 into 9c8eb2b
Browse files Browse the repository at this point in the history
  • Loading branch information
srmainwaring authored Feb 7, 2022
2 parents 9c8eb2b + 441b348 commit e47886d
Show file tree
Hide file tree
Showing 6 changed files with 286 additions and 26 deletions.
2 changes: 1 addition & 1 deletion examples/waves/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ include_directories(SYSTEM
${PROJECT_BINARY_DIR}
)

find_package(ignition-rendering6)
find_package(ignition-rendering7)

set(TARGET_THIRD_PARTY_DEPENDS "")

Expand Down
18 changes: 3 additions & 15 deletions examples/waves/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -87,18 +87,6 @@ bool g_initContext = false;
GLXDrawable g_glutDrawable;
#endif

double g_offset = 0.0;

int g_seed[1] = {0};
float g_resolution[2] = {400, 200};
float g_color[3] = {1.0, 1.0, 1.0};
float g_adjustments[16] = {
0, 0, 0, 0.0005,
0, 0, 0, 0,
0, 0, 0, 0,
0, 0, 0, 0
};

// view control variables
ir::RayQueryPtr g_rayQuery;
ir::OrbitViewController g_viewControl;
Expand Down Expand Up @@ -341,9 +329,9 @@ void initCamera(ir::CameraPtr _camera)
void initUniforms()
{
ir::NodePtr node = g_camera->Parent();
ir::VisualPtr sphere =
ir::VisualPtr waves =
std::dynamic_pointer_cast<ir::Visual>(node->ChildByName("waves"));
ir::MaterialPtr shader = sphere->Material();
ir::MaterialPtr shader = waves->Material();
if (!shader)
return;

Expand Down Expand Up @@ -372,7 +360,7 @@ void initUniforms()
(*g_vsParams)["bumpSpeed"].InitializeBuffer(2);
(*g_vsParams)["bumpSpeed"].UpdateBuffer(bumpSpeed);

float amplitude = 0.7f;
float amplitude = 3.0f;
float amplitudeV[3] = {0.6f * amplitude, 0.4f * amplitude, 0.3f * amplitude};
(*g_vsParams)["amplitude"].InitializeBuffer(3);
(*g_vsParams)["amplitude"].UpdateBuffer(amplitudeV);
Expand Down
31 changes: 21 additions & 10 deletions examples/waves/Main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,16 @@ using namespace rendering;
const std::string vertexShaderGLSL330File = "GerstnerWaves_vs_330.glsl";
const std::string fragmentShaderGLSL330File = "GerstnerWaves_fs_330.glsl";

const std::string vertexShaderMetalFile = "GerstnerWaves_vs.metal";
const std::string fragmentShaderMetalFile = "GerstnerWaves_fs.metal";

const std::string RESOURCE_PATH =
ignition::common::joinPaths(std::string(PROJECT_BINARY_PATH), "media");

//////////////////////////////////////////////////
void buildScene(ScenePtr _scene, const std::string &_engineName)
void buildScene(ScenePtr _scene,
const std::string &_engineName,
const std::map<std::string, std::string>& _params)
{
// initialize _scene
_scene->SetAmbientLight(0.8, 0.8, 0.8);
Expand All @@ -69,8 +74,16 @@ void buildScene(ScenePtr _scene, const std::string &_engineName)
std::string vertexShaderFile;
std::string fragmentShaderFile;

vertexShaderFile = vertexShaderGLSL330File;
fragmentShaderFile = fragmentShaderGLSL330File;
if (_params.find("metal") != _params.end())
{
vertexShaderFile = vertexShaderMetalFile;
fragmentShaderFile = fragmentShaderMetalFile;
}
else
{
vertexShaderFile = vertexShaderGLSL330File;
fragmentShaderFile = fragmentShaderGLSL330File;
}

// create shader materials
// path to look for vertex and fragment shader parameters
Expand All @@ -85,7 +98,7 @@ void buildScene(ScenePtr _scene, const std::string &_engineName)
shader->SetVertexShader(vertexShaderPath);
shader->SetFragmentShader(fragmentShaderPath);

// create box visual
// create waves visual
VisualPtr waves = _scene->CreateVisual("waves");
MeshDescriptor descriptor;
descriptor.meshName = common::joinPaths(RESOURCE_PATH, "mesh.dae");
Expand All @@ -100,11 +113,11 @@ void buildScene(ScenePtr _scene, const std::string &_engineName)

// create camera
CameraPtr camera = _scene->CreateCamera("camera");
camera->SetLocalPosition(0, 0.0, 0.5);
camera->SetLocalPosition(0, 0.0, 3.5);
camera->SetLocalRotation(0.0, 0.0, 0.0);
camera->SetImageWidth(800);
camera->SetImageHeight(600);
camera->SetAntiAliasing(2);
camera->SetAntiAliasing(4);
camera->SetAspectRatio(1.333);
camera->SetHFOV(IGN_PI / 2);
root->AddChild(camera);
Expand All @@ -123,7 +136,7 @@ CameraPtr createCamera(const std::string &_engineName,
return CameraPtr();
}
ScenePtr scene = engine->CreateScene("scene");
buildScene(scene, _engineName);
buildScene(scene, _engineName, _params);

// return camera sensor
SensorPtr sensor = scene->SensorByName("camera");
Expand Down Expand Up @@ -164,9 +177,7 @@ int main(int _argc, char** _argv)
{
if (graphicsApi == GraphicsAPI::METAL)
{
// \todo(anyone) uncomment once metal shaders are available
// params["metal"] = "1";
ignerr << "Metal shaders are not implemented yet. Using GLSL" << std::endl;
params["metal"] = "1";
}
}
else
Expand Down
83 changes: 83 additions & 0 deletions examples/waves/media/GerstnerWaves_fs.metal
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
// Copyright (c) 2016 The UUV Simulator Authors.
// All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <metal_stdlib>
using namespace metal;

////////// Input parameters //////////
// Colors
struct Params
{
float4 deepColor;
float4 shallowColor;
float fresnelPower;
float hdrMultiplier;
};

////////// Input computed in vertex shader //////////
struct PS_INPUT
{
float2 uv0;
float3 B;
float3 T;
float3 N;
float3 eyeVec;
float2 bumpCoord;
};

fragment float4 main_metal
(
PS_INPUT inPs [[stage_in]],
texturecube<float> cubeMap [[texture(0)]],
texture2d<float> bumpMap [[texture(1)]],
sampler cubeMapSampler [[sampler(0)]],
sampler bumpMapSampler [[sampler(1)]],
constant Params &p [[buffer(PARAMETER_SLOT)]]
)
{
// Apply bump mapping to normal vector to make waves look more detailed:
float4 bump = bumpMap.sample(bumpMapSampler, inPs.bumpCoord)*2.0 - 1.0;
float3x3 rotMatrix(inPs.B, inPs.T, inPs.N);
float3 N = normalize(rotMatrix * bump.xyz);

// Reflected ray:
float3 E = normalize(inPs.eyeVec);
float3 R = reflect(E, N);

// Negate z for use with the skybox texture that comes with ign-rendering
R = float3(R.x, R.y, -R.z);

// uncomment this line if using other textures that are Y up
// Gazebo requires rotated cube map lookup.
// R = float3(R.x, R.z, R.y);

// Get environment color of reflected ray:
float4 envColor = cubeMap.sample(cubeMapSampler, R);

// Cheap hdr effect:
envColor.rgb *= (envColor.r+envColor.g+envColor.b)*p.hdrMultiplier;

// Compute refraction ratio (Fresnel):
float facing = 1.0 - dot(-E, N);
float waterEnvRatio = clamp(pow(facing, p.fresnelPower), 0.0, 1.0);

// Refracted ray only considers deep and shallow water colors:
float4 waterColor = mix(p.shallowColor, p.deepColor, facing);

// Perform linear interpolation between reflection and refraction.
float4 color = mix(waterColor, envColor, waterEnvRatio);

return float4(color.xyz, 0.1);
}
171 changes: 171 additions & 0 deletions examples/waves/media/GerstnerWaves_vs.metal
Original file line number Diff line number Diff line change
@@ -0,0 +1,171 @@
// Copyright (c) 2016 The UUV Simulator Authors.
// All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.s


// Copyright (c) 2019 Rhys Mainwaring.
//
// Modified to accept vector parameters and use the form
// for Gerstner waves published in:
//
// Jerry Tessendorf, "Simulating Ocean Water", 1999-2004
//
// theta = k * dir . x - omega * t
//
// px = x - dir.x * a * k * sin(theta)
// py = y - dir.y * a * k * sin(theta)
// pz = a * k * cos(theta)
//
// k is the wavenumber
// omega is the angular frequency
//
// The derivative terms (Tangent, Binormal, Normal) have been
// updated to be consistent with this convention.


// original concept:
// https://developer.nvidia.com/gpugems/gpugems/part-i-natural-effects/chapter-1-effective-water-simulation-physical-models

#include <metal_stdlib>
using namespace metal;

struct VS_INPUT
{
float4 position [[attribute(VES_POSITION)]];
float2 uv0 [[attribute(VES_TEXTURE_COORDINATES0)]];
};

/////////// Input parameters //////////
// Waves
struct Params
{
float4x4 worldviewproj_matrix;
int Nwaves;
float3 camera_position_object_space;
float rescale;
float2 bumpScale;
float2 bumpSpeed;
float t;
float3 amplitude;
float3 wavenumber;
float3 omega;
float3 steepness;
float2 dir0;
float2 dir1;
float2 dir2;
float tau;
};

/////////// Output variables to fragment shader //////////
struct PS_INPUT
{
float4 gl_Position [[position]];
float2 uv0;
float3 B;
float3 T;
float3 N;
float3 eyeVec;
float2 bumpCoord;
};

// Compute linear combination of Gerstner waves as described in
// GPU Gems, chapter 01: "Effective Water Simulation from Physical Models"
// http://http.developer.nvidia.com/GPUGems/gpugems_ch01.html

// Information regarding a single wave
struct WaveParameters {
WaveParameters(float _k, float _a, float _omega, float2 _d, float _q) :
k(_k), a(_a), omega(_omega), d(_d), q(_q) {}

float k; // wavenumber
float a; // amplitude
float omega; // phase constant of speed
float2 d; // horizontal direction of wave
float q; // steepness for Gerstner wave (q=0: rolling sine waves)
};

vertex PS_INPUT main_metal
(
VS_INPUT input [[stage_in]],
constant Params &p [[buffer(PARAMETER_SLOT)]]
)
{
PS_INPUT outVs;

// Use combination of three waves. Values here are chosen rather arbitrarily.
// Other parameters might lead to better-looking waves.

WaveParameters waves[3] = {
WaveParameters(p.wavenumber.x, p.amplitude.x, p.omega.x, p.dir0.xy, p.steepness.x),
WaveParameters(p.wavenumber.y, p.amplitude.y, p.omega.y, p.dir1.xy, p.steepness.y),
WaveParameters(p.wavenumber.z, p.amplitude.z, p.omega.z, p.dir2.xy, p.steepness.z)
};

float4 P = input.position;

// Iteratively compute binormal, tangent, and normal vectors:
float3 B = float3(1.0, 0.0, 0.0);
float3 T = float3(0.0, 1.0, 0.0);
float3 N = float3(0.0, 0.0, 1.0);

// Wave synthesis using linear combination of Gerstner waves
for(int i = 0; i < p.Nwaves; ++i)
{
// Evaluate wave equation:
float k = waves[i].k;
float a = waves[i].a * (1.0 - exp(-1.0*p.t/p.tau));
float q = waves[i].q;
float dx = waves[i].d.x;
float dy = waves[i].d.y;
float theta = dot(waves[i].d, P.xy)*k - p.t*waves[i].omega;
float c = cos(theta);
float s = sin(theta);

// Displacement of point due to wave (Eq. 9)
P.x -= q*a*dx*s;
P.y -= q*a*dx*s;
P.z += a*c;

// Modify normals due to wave displacement (Eq. 10-12)
float ka = a*k;
float qkac = q*ka*c;
float kas = ka*s;
float dxy = dx*dy;

B += float3(-qkac*dx*dx, -qkac*dxy, -kas*dx);
T += float3(-qkac*dxy, -qkac*dy*dy, -kas*dy);
N += float3(dx*kas, dy*kas, -qkac);
}

// Compute (Surf2World * Rescale) matrix
B = normalize(B)*p.rescale;
T = normalize(T)*p.rescale;
N = normalize(N);
// outVs won't accept float3x3, so pass components
outVs.B = B;
outVs.T = T;
outVs.N = N;

outVs.gl_Position = p.worldviewproj_matrix * P;

// Compute texture coordinates for bump map
outVs.bumpCoord = input.uv0.xy * p.bumpScale + p.t * p.bumpSpeed;

outVs.eyeVec = P.xyz - p.camera_position_object_space; // eye position in vertex space

// Pass texture coordinates to frag shader
outVs.uv0 = input.uv0.xy;

return outVs;
}
7 changes: 7 additions & 0 deletions ogre2/src/Ogre2Material.cc
Original file line number Diff line number Diff line change
Expand Up @@ -762,6 +762,13 @@ void Ogre2Material::UpdateShaderParams(ConstShaderParamsPtr _params,
else if (type == ShaderParam::ParamType::PARAM_TEXTURE_CUBE)
{
texUnit->setCubicTextureName(baseName, true);
// must apply this check for Metal rendering to work
// (i.e. not segfault). See the discussion in:
// https://github.com/ignitionrobotics/ign-rendering/pull/541
if (texUnit->isLoaded())
{
texUnit->_load();
}
}
else
{
Expand Down

0 comments on commit e47886d

Please sign in to comment.