Skip to content

Commit

Permalink
[Metal] update custom_shaders_uniform example
Browse files Browse the repository at this point in the history
- Add metal shaders to the custom_shaders_uniforms example
- Set reflection pair hint for Metal pixel shaders to ensure params are set

Select materials shader language depending on graphics API

- Add a GraphicsAPI property to the private data of Ogre2Material
- Switch the language used for the GPU program depending on the API
- Set the default API to OpenGL.
- To do: missing a method to set the graphics API when creating a material

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Feb 4, 2022
1 parent 1e711f6 commit cf94549
Show file tree
Hide file tree
Showing 4 changed files with 165 additions and 15 deletions.
26 changes: 19 additions & 7 deletions examples/custom_shaders_uniforms/Main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,13 +49,18 @@ const std::string fragmentShaderGLSLFile = "fragment_shader.glsl";
const std::string vertexShaderGLSL330File = "vertex_shader_330.glsl";
const std::string fragmentShaderGLSL330File = "fragment_shader_330.glsl";

const std::string vertexShaderMetalFile = "vertex_shader.metal";
const std::string fragmentShaderMetalFile = "fragment_shader.metal";

//! [init shaders variables]

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.3, 0.3, 0.3);
Expand All @@ -72,8 +77,17 @@ void buildScene(ScenePtr _scene, const std::string &_engineName)
std::string fragmentShaderFile;
if (_engineName == "ogre2")
{
vertexShaderFile = vertexShaderGLSL330File;
fragmentShaderFile = fragmentShaderGLSL330File;
auto it = _params.find("metal");
if (it != _params.end() && it->second == "1")
{
vertexShaderFile = vertexShaderMetalFile;
fragmentShaderFile = fragmentShaderMetalFile;
}
else
{
vertexShaderFile = vertexShaderGLSL330File;
fragmentShaderFile = fragmentShaderGLSL330File;
}
}
else
{
Expand Down Expand Up @@ -132,7 +146,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 @@ -173,9 +187,7 @@ int main(int _argc, char** _argv)
if (engineName.compare("ogre2") == 0
&& 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";
}

CameraPtr camera = createCamera(engineName, params);
Expand Down
59 changes: 59 additions & 0 deletions examples/custom_shaders_uniforms/media/fragment_shader.metal
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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;

#define M_PI 3.1415926535897932384626433832795

struct PS_INPUT
{
float4 interpolatedPosition;
};

struct Params
{
int u_seed;
float2 u_resolution;
float3 u_color;
float4x4 u_adjustments;
};

float random(float2 uv, float seed) {
return fract(sin(fmod(dot(uv, float2(12.9898, 78.233))
+ 1113.1 * seed, M_PI)) * 43758.5453);
}

fragment float4 main_metal
(
PS_INPUT inPs [[stage_in]],
constant Params &p [[buffer(PARAMETER_SLOT)]]
)
{
// Metal matrices are row major: a[row][col]
float a0 = p.u_adjustments[0][0];
float a1 = p.u_adjustments[0][1];
float a2 = p.u_adjustments[0][2];
float a3 = p.u_adjustments[0][3];

float3 a = float3(a0, a1, a2);
float2 b = float2(distance(float3(inPs.interpolatedPosition.xyw), a)) * a3;
float2 normalizedFragCoord = b / p.u_resolution;

float color = random(normalizedFragCoord, float(p.u_seed));
return float4(color * p.u_color, 1.0);
}
49 changes: 49 additions & 0 deletions examples/custom_shaders_uniforms/media/vertex_shader.metal
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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;

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

struct PS_INPUT
{
float4 gl_Position [[position]];
float4 interpolatedPosition;
};

struct Params
{
float4x4 worldviewproj_matrix;
};

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

outVs.gl_Position = p.worldviewproj_matrix * input.position;
outVs.interpolatedPosition = outVs.gl_Position;

return outVs;
}
46 changes: 38 additions & 8 deletions ogre2/src/Ogre2Material.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include <ignition/common/Filesystem.hh>
#include <ignition/common/Image.hh>

#include "ignition/rendering/GraphicsAPI.hh"
#include "ignition/rendering/ShaderParams.hh"
#include "ignition/rendering/ShaderType.hh"
#include "ignition/rendering/ogre2/Ogre2Material.hh"
Expand All @@ -51,6 +52,9 @@
/// \brief Private data for the Ogre2Material class
class ignition::rendering::Ogre2MaterialPrivate
{
/// \brief The graphics API to use
public: GraphicsAPI graphicsAPI{GraphicsAPI::OPENGL};

/// \brief Ogre stores the name using hashes. This variable will
/// store the material hash name
public: std::string hashName;
Expand All @@ -66,6 +70,20 @@ class ignition::rendering::Ogre2MaterialPrivate

/// \brief Parameters to be bound to the fragment shader
public: ShaderParamsPtr fragmentShaderParams;

/// \brief Returns the shader language code
public: std::string shaderLanguageCode() const
{
switch (this->graphicsAPI)
{
case GraphicsAPI::OPENGL:
return "glsl";
case GraphicsAPI::METAL:
return "metal";
default:
return "invalid";
}
}
};

using namespace ignition;
Expand Down Expand Up @@ -752,8 +770,11 @@ void Ogre2Material::UpdateShaderParams(ConstShaderParamsPtr _params,
<< name_param.first << std::endl;
continue;
}
// set the texture map index
_ogreParams->setNamedConstant(name_param.first, &texIndex, 1, 1);
if (this->dataPtr->graphicsAPI == GraphicsAPI::OPENGL)
{
// set the texture map index
_ogreParams->setNamedConstant(name_param.first, &texIndex, 1, 1);
}
}
}
}
Expand Down Expand Up @@ -1090,13 +1111,10 @@ void Ogre2Material::SetVertexShader(const std::string &_path)
Ogre::HighLevelGpuProgramManager::getSingletonPtr()->createProgram(
"_ign_" + baseName,
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
"glsl", Ogre::GpuProgramType::GPT_VERTEX_PROGRAM);
this->dataPtr->shaderLanguageCode(),
Ogre::GpuProgramType::GPT_VERTEX_PROGRAM);

vertexShader->setSourceFile(_path);

Ogre::GpuProgramParametersSharedPtr params =
vertexShader->getDefaultParameters();

vertexShader->load();

assert(vertexShader->isLoaded());
Expand Down Expand Up @@ -1145,7 +1163,19 @@ void Ogre2Material::SetFragmentShader(const std::string &_path)
Ogre::HighLevelGpuProgramManager::getSingleton().createProgram(
"_ign_" + baseName,
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
"glsl", Ogre::GpuProgramType::GPT_FRAGMENT_PROGRAM);
this->dataPtr->shaderLanguageCode(),
Ogre::GpuProgramType::GPT_FRAGMENT_PROGRAM);

// set shader language specific parameters
if (this->dataPtr->graphicsAPI == GraphicsAPI::METAL)
{
// must set reflection pair hint for Metal fragment shaders
// otherwise the parameters (uniforms) will not be set correctly
std::string paramName("shader_reflection_pair_hint");
std::string paramValue =
"_ign_" + common::basename(this->dataPtr->vertexShaderPath);
fragmentShader->setParameter(paramName, paramValue);
}

fragmentShader->setSourceFile(_path);
fragmentShader->load();
Expand Down

0 comments on commit cf94549

Please sign in to comment.