Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Extend ogre 1.x custom shaders support #908

Merged
merged 8 commits into from
Oct 5, 2023
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion examples/waves/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -339,7 +339,7 @@ void initUniforms()
g_vsParams = shader->VertexShaderParams();

auto engine = g_camera->Scene()->Engine();
if (engine->Name() == "ogre2")
if (engine->Name() == "ogre2" || engine->Name() == "ogre")
{
// worldviewproj_matrix is a constant defined by ogre.
// Here we add a line to add this constant to the params.
Expand Down
16 changes: 8 additions & 8 deletions examples/waves/Main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,9 @@
using namespace gz;
using namespace rendering;

const std::string vertexShaderGLSLFile = "GerstnerWaves_vs.glsl";
const std::string fragmentShaderGLSLFile = "GerstnerWaves_fs.glsl";

const std::string vertexShaderGLSL330File = "GerstnerWaves_vs_330.glsl";
const std::string fragmentShaderGLSL330File = "GerstnerWaves_fs_330.glsl";

Expand Down Expand Up @@ -79,6 +82,11 @@ void buildScene(ScenePtr _scene,
vertexShaderFile = vertexShaderMetalFile;
fragmentShaderFile = fragmentShaderMetalFile;
}
else if (_engineName == "ogre")
{
vertexShaderFile = vertexShaderGLSLFile;
fragmentShaderFile = fragmentShaderGLSLFile;
}
else
{
vertexShaderFile = vertexShaderGLSL330File;
Expand Down Expand Up @@ -180,14 +188,6 @@ int main(int _argc, char** _argv)
params["metal"] = "1";
}
}
else
{
// todo(anyone) Passing textures to custom shaders is currently
// only available in ogre2
engineName = "ogre2";
gzerr << "Only ogre2 engine is supported. Switching to use ogre2."
<< std::endl;
}

CameraPtr camera = createCamera(engineName, params);
if (camera)
Expand Down
68 changes: 68 additions & 0 deletions examples/waves/media/GerstnerWaves_fs.glsl
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
// 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.

#version 150

////////// Input parameters //////////
// Textures
uniform sampler2D bumpMap;
uniform samplerCube cubeMap;

// Colors
uniform vec4 deepColor;
uniform vec4 shallowColor;
uniform float fresnelPower;
uniform float hdrMultiplier;

////////// Input computed in vertex shader //////////
varying mat3 rotMatrix;
varying vec3 eyeVec;
varying vec2 bumpCoord;

void main()
{
// Apply bump mapping to normal vector to make waves look more detailed:
vec4 bump = texture2D(bumpMap, bumpCoord) * 2.0 - 1.0;
vec3 N = normalize(rotMatrix * bump.xyz);

// Reflected ray:
vec3 E = normalize(eyeVec);
vec3 R = reflect(E, N);

// negate z for use with the skybox texture that comes with gz-rendering
R = vec3(R.x, R.y, -R.z);

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

// Get environment color of reflected ray:
vec4 envColor = textureCube(cubeMap, R, 0.0);

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

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

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

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

gl_FragColor = vec4(color.xyz, 0.9);
}
139 changes: 139 additions & 0 deletions examples/waves/media/GerstnerWaves_vs.glsl
Original file line number Diff line number Diff line change
@@ -0,0 +1,139 @@
// 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.
//

#version 150

in vec4 vertex;
in vec4 uv0;
uniform mat4 worldviewproj_matrix;

/////////// Input parameters //////////
// Waves
uniform int Nwaves;
uniform vec3 camera_position_object_space;
uniform float rescale;
uniform vec2 bumpScale;
uniform vec2 bumpSpeed;
uniform float t;
uniform vec3 amplitude;
uniform vec3 wavenumber;
uniform vec3 omega;
uniform vec3 steepness;
uniform vec2 dir0;
uniform vec2 dir1;
uniform vec2 dir2;
uniform float tau;

/////////// Output variables to fragment shader //////////
varying mat3 rotMatrix;
varying vec3 eyeVec;
varying vec2 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 {
float k; // wavenumber
float a; // amplitude
float omega; // phase constant of speed
vec2 d; // horizontal direction of wave
float q; // steepness for Gerstner wave (q=0: rolling sine waves)
};


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

WaveParameters waves[3];

waves[0] = WaveParameters(wavenumber.x, amplitude.x, omega.x, dir0.xy, steepness.x);
waves[1] = WaveParameters(wavenumber.y, amplitude.y, omega.y, dir1.xy, steepness.y);
waves[2] = WaveParameters(wavenumber.z, amplitude.z, omega.z, dir2.xy, steepness.z);

vec4 P = vertex;

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

// Wave synthesis using linear combination of Gerstner waves
for(int i = 0; i < Nwaves; ++i)
{
// Evaluate wave equation:
float k = waves[i].k;
float a = waves[i].a * (1.0 - exp(-1.0*t/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 - 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 += vec3(-qkac*dx*dx, -qkac*dxy, -kas*dx);
T += vec3(-qkac*dxy, -qkac*dy*dy, -kas*dy);
N += vec3(dx*kas, dy*kas, -qkac);
}

// Compute (Surf2World * Rescale) matrix
B = normalize(B)*rescale;
T = normalize(T)*rescale;
N = normalize(N);
rotMatrix = mat3(B, T, N);

gl_Position = worldviewproj_matrix * P;

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

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

97 changes: 97 additions & 0 deletions ogre/src/OgreMaterial.cc
Original file line number Diff line number Diff line change
Expand Up @@ -407,6 +407,25 @@ void OgreMaterial::UpdateShaderParams(ConstShaderParamsPtr _params,
{
for (const auto &name_param : *_params)
{
auto *constantDef =
Ogre::GpuProgramParameters::getAutoConstantDefinition(name_param.first);
if (constantDef)
{
_ogreParams->setNamedAutoConstant(name_param.first, constantDef->acType);
continue;
}

if (!_ogreParams->_findNamedConstantDefinition(name_param.first) &&
!(OgreRenderEngine::Instance()->GraphicsAPI() !=
GraphicsAPI::OPENGL &&
(ShaderParam::PARAM_TEXTURE == name_param.second.Type() ||
ShaderParam::PARAM_TEXTURE_CUBE == name_param.second.Type())))
{
gzwarn << "Unable to find GPU program parameter: "
<< name_param.first << std::endl;
continue;
}

if (ShaderParam::PARAM_FLOAT == name_param.second.Type())
{
float value;
Expand Down Expand Up @@ -441,6 +460,84 @@ void OgreMaterial::UpdateShaderParams(ConstShaderParamsPtr _params,
_ogreParams->setNamedConstant(name_param.first,
reinterpret_cast<int*>(buffer.get()), count, multiple);
}
else if (ShaderParam::PARAM_TEXTURE == name_param.second.Type() ||
ShaderParam::PARAM_TEXTURE_CUBE == name_param.second.Type())
{
// add the textures to the resource path
std::string value;
uint32_t uvSetIndex = 0;
name_param.second.Value(value, uvSetIndex);
ShaderParam::ParamType type = name_param.second.Type();

std::string baseName = value;
std::string dirPath = value;
if (common::isFile(value))
{
baseName = common::basename(value);
size_t idx = value.rfind(baseName);
if (idx != std::string::npos)
{
dirPath = value.substr(0, idx);
if (!dirPath.empty() &&
!Ogre::ResourceGroupManager::getSingleton().resourceLocationExists(
dirPath))
{
Ogre::ResourceGroupManager::getSingleton().addResourceLocation(
dirPath, "FileSystem", this->ogreGroup);
}
}
}
else
{
gzerr << "Shader param texture not found: " << value << std::endl;
continue;
}

// get the material and create the texture unit state if it does not exist
auto texUnit = this->ogrePass->getTextureUnitState(name_param.first);
if (!texUnit)
{
texUnit = this->ogrePass->createTextureUnitState();
texUnit->setName(name_param.first);
}
// make sure to cast to int before calling setNamedConstant later
// to set the texture index
int texIndex = static_cast<int>(
this->ogrePass->getTextureUnitStateIndex(texUnit));

// set texture coordinate set
texUnit->setTextureCoordSet(uvSetIndex);

// regular 2d texture
if (type == ShaderParam::ParamType::PARAM_TEXTURE)
{
texUnit->setTextureName(baseName);
}
// cube maps
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/gazebosim/gz-rendering/pull/541
if (texUnit->isLoaded())
{
texUnit->_load();
}
}
else
{
gzerr << "Unrecognized texture type set for shader param: "
<< name_param.first << std::endl;
iche033 marked this conversation as resolved.
Show resolved Hide resolved
continue;
}
if (OgreRenderEngine::Instance()->GraphicsAPI() ==
GraphicsAPI::OPENGL)
{
// set the texture map index
_ogreParams->setNamedConstant(name_param.first, &texIndex, 1, 1);
}
}
}
}

Expand Down
2 changes: 1 addition & 1 deletion ogre2/src/Ogre2Material.cc
Original file line number Diff line number Diff line change
Expand Up @@ -936,7 +936,7 @@ void Ogre2Material::UpdateShaderParams(ConstShaderParamsPtr _params,
continue;
}

// get the material and create the texture unit state it does not exist
// get the material and create the texture unit state if it does not exist
auto mat = this->Material();
auto pass = mat->getTechnique(0u)->getPass(0);
auto texUnit = pass->getTextureUnitState(name_param.first);
Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ set(tests
sky
thermal_camera
load_unload
waves
wide_angle_camera
)

Expand Down
Loading