diff --git a/examples/worlds/shader_param.sdf b/examples/worlds/shader_param.sdf
index db3d48ca78..1aab09d7d4 100644
--- a/examples/worlds/shader_param.sdf
+++ b/examples/worlds/shader_param.sdf
@@ -167,6 +167,8 @@ ShaderParam visual plugin over time.
1.0 1.0 1.0
0.8 0.8 0.8
+
+ false
@@ -177,43 +179,21 @@ ShaderParam visual plugin over time.
-0.5 0.1 -0.9
-
- true
-
-
-
-
- 0 0 1
- 100 100
-
-
-
-
-
-
- 0 0 1
- 100 100
-
-
-
- 0.8 0.8 0.8 1
- 0.8 0.8 0.8 1
- 0.8 0.8 0.8 1
-
-
-
-
-
- 0 0.0 0.5 0 0 0
deformable_sphere
- 3 0 0 0 0 0
+ 0 0 1.5 0 0 0
https://fuel.ignitionrobotics.org/1.0/openrobotics/models/deformable_sphere
+
+ waves
+ 0 0 0 0 0 0
+ https://fuel.ignitionrobotics.org/1.0/openrobotics/models/waves
+
+
true
- 2.5 0 0.5 0 0.0 3.14
+ 2.5 0 1.5 0 0.0 3.14
0.05 0.05 0.05 0 0 0
diff --git a/src/systems/shader_param/ShaderParam.cc b/src/systems/shader_param/ShaderParam.cc
index feab7709b2..973a7cac08 100644
--- a/src/systems/shader_param/ShaderParam.cc
+++ b/src/systems/shader_param/ShaderParam.cc
@@ -51,8 +51,8 @@ class ignition::gazebo::systems::ShaderParamPrivate
/// \brief shader type: vertex or fragment
public: std::string shader;
- /// \brief variable type: int, float, float_array, int_array
- /// \todo(anyone) support samplers
+ /// \brief variable type: int, float, float_array, int_array,
+ /// texture, texture_cube
public: std::string type;
/// \brief variable name of param
@@ -60,6 +60,9 @@ class ignition::gazebo::systems::ShaderParamPrivate
/// \brief param value
public: std::string value;
+
+ /// \brief Any additional arguments
+ public: std::vector args;
};
/// \brief Path to vertex shader
@@ -98,6 +101,9 @@ class ignition::gazebo::systems::ShaderParamPrivate
/// \brief Current sim time
public: std::chrono::steady_clock::duration currentSimTime;
+ /// \brief Path to model
+ public: std::string modelPath;
+
/// \brief All rendering operations must happen within this call
public: void OnUpdate();
};
@@ -149,11 +155,29 @@ void ShaderParam::Configure(const Entity &_entity,
spv.name = paramName;
spv.value = value;
spv.type = type;
+
+ if (paramElem->HasElement("arg"))
+ {
+ sdf::ElementPtr argElem = paramElem->GetElement("arg");
+ while (argElem)
+ {
+ spv.args.push_back(argElem->Get());
+ argElem = argElem->GetNextElement("arg");
+ }
+ }
+
this->dataPtr->shaderParams.push_back(spv);
paramElem = paramElem->GetNextElement("param");
}
}
+ if (this->dataPtr->modelPath.empty())
+ {
+ auto modelEntity = topLevelModel(_entity, _ecm);
+ this->dataPtr->modelPath =
+ _ecm.ComponentData(modelEntity).value();
+ }
+
// parse path to shaders
if (sdf->HasElement("shader"))
{
@@ -166,15 +190,14 @@ void ShaderParam::Configure(const Entity &_entity,
}
else
{
- auto modelEntity = topLevelModel(_entity, _ecm);
- auto modelPath =
- _ecm.ComponentData(modelEntity);
sdf::ElementPtr vertexElem = shaderElem->GetElement("vertex");
this->dataPtr->vertexShaderUri = common::findFile(
- asFullPath(vertexElem->Get(), modelPath.value()));
+ asFullPath(vertexElem->Get(),
+ this->dataPtr->modelPath));
sdf::ElementPtr fragmentElem = shaderElem->GetElement("fragment");
this->dataPtr->fragmentShaderUri = common::findFile(
- asFullPath(fragmentElem->Get(), modelPath.value()));
+ asFullPath(fragmentElem->Get(),
+ this->dataPtr->modelPath));
}
}
@@ -263,14 +286,12 @@ void ShaderParamPrivate::OnUpdate()
// this is only done once
for (const auto & spv : this->shaderParams)
{
- std::vector values = common::split(spv.value, " ");
-
- int intValue = 0;
- float floatValue = 0;
- std::vector floatArrayValue;
-
- rendering::ShaderParam::ParamType paramType =
- rendering::ShaderParam::PARAM_NONE;
+ // TIME is reserved keyword for sim time
+ if (spv.value == "TIME")
+ {
+ this->timeParams.push_back(spv);
+ continue;
+ }
rendering::ShaderParamsPtr params;
if (spv.shader == "fragment")
@@ -283,92 +304,115 @@ void ShaderParamPrivate::OnUpdate()
}
// if no is specified, this could be a constant
- if (values.empty())
+ if (spv.value.empty())
+ {
+ // \todo handle args for constants in ign-rendering
+ (*params)[spv.name] = 1;
+ continue;
+ }
+
+ // handle texture params
+ if (spv.type == "texture")
{
- // \todo handle args for constants
- (*params)[spv.name] = intValue;
+ unsigned int uvSetIndex = spv.args.empty() ? 0u :
+ static_cast(std::stoul(spv.args[0]));
+ std::string texPath = common::findFile(
+ asFullPath(spv.value, this->modelPath));
+ (*params)[spv.name].SetTexture(texPath,
+ rendering::ShaderParam::ParamType::PARAM_TEXTURE, uvSetIndex);
}
- // float / int
- else if (values.size() == 1u)
+ else if (spv.type == "texture_cube")
+ {
+ unsigned int uvSetIndex = spv.args.empty() ? 0u :
+ static_cast(std::stoul(spv.args[0]));
+ std::string texPath = common::findFile(
+ asFullPath(spv.value, this->modelPath));
+ (*params)[spv.name].SetTexture(texPath,
+ rendering::ShaderParam::ParamType::PARAM_TEXTURE_CUBE, uvSetIndex);
+ }
+ // handle int, float, int_array, and float_array params
+ else
{
- std::string str = values[0];
+ std::vector values = common::split(spv.value, " ");
- // TIME is reserved keyword for sim time
- if (str == "TIME")
- {
- this->timeParams.push_back(spv);
- continue;
- }
+ int intValue = 0;
+ float floatValue = 0;
+ std::vector floatArrayValue;
- // if is not empty, respect the specified type
- if (!spv.type.empty())
+ rendering::ShaderParam::ParamType paramType =
+ rendering::ShaderParam::PARAM_NONE;
+
+ // float / int
+ if (values.size() == 1u)
{
- if (spv.type == "int")
- {
- intValue = std::stoi(str);
- paramType = rendering::ShaderParam::PARAM_INT;
- }
- else if (spv.type == "float")
+ std::string str = values[0];
+
+ // if is not empty, respect the specified type
+ if (!spv.type.empty())
{
- floatValue = std::stof(str);
- paramType = rendering::ShaderParam::PARAM_FLOAT;
+ if (spv.type == "int")
+ {
+ intValue = std::stoi(str);
+ paramType = rendering::ShaderParam::PARAM_INT;
+ }
+ else if (spv.type == "float")
+ {
+ floatValue = std::stof(str);
+ paramType = rendering::ShaderParam::PARAM_FLOAT;
+ }
}
+ // else do our best guess at what the type is
else
{
- // \todo(anyone) support texture samplers
+ std::string::size_type sz;
+ int n = std::stoi(str, &sz);
+ if ( sz == str.size())
+ {
+ intValue = n;
+ paramType = rendering::ShaderParam::PARAM_INT;
+ }
+ else
+ {
+ floatValue = std::stof(str);
+ paramType = rendering::ShaderParam::PARAM_FLOAT;
+ }
}
}
- // else do our best guess at what the type is
+ // arrays
else
{
- std::string::size_type sz;
- int n = std::stoi(str, &sz);
- if ( sz == str.size())
+ // int array
+ if (!spv.type.empty() && spv.type == "int_array")
{
- intValue = n;
- paramType = rendering::ShaderParam::PARAM_INT;
+ for (const auto &v : values)
+ floatArrayValue.push_back(std::stoi(v));
+ paramType = rendering::ShaderParam::PARAM_INT_BUFFER;
}
+ // treat everything else as float_array
else
{
- floatValue = std::stof(str);
- paramType = rendering::ShaderParam::PARAM_FLOAT;
+ for (const auto &v : values)
+ floatArrayValue.push_back(std::stof(v));
+ paramType = rendering::ShaderParam::PARAM_FLOAT_BUFFER;
}
}
- }
- // arrays
- else
- {
- // int array
- if (!spv.type.empty() && spv.type == "int_array")
+
+ // set the params
+ if (paramType == rendering::ShaderParam::PARAM_INT)
{
- for (const auto &v : values)
- floatArrayValue.push_back(std::stoi(v));
- paramType = rendering::ShaderParam::PARAM_INT_BUFFER;
+ (*params)[spv.name] = intValue;
}
- // treat everything else as float_array
- else
+ else if (paramType == rendering::ShaderParam::PARAM_FLOAT)
{
- for (const auto &v : values)
- floatArrayValue.push_back(std::stof(v));
- paramType = rendering::ShaderParam::PARAM_FLOAT_BUFFER;
+ (*params)[spv.name] = floatValue;
+ }
+ else if (paramType == rendering::ShaderParam::PARAM_INT_BUFFER ||
+ paramType == rendering::ShaderParam::PARAM_FLOAT_BUFFER)
+ {
+ (*params)[spv.name].InitializeBuffer(floatArrayValue.size());
+ float *fv = &floatArrayValue[0];
+ (*params)[spv.name].UpdateBuffer(fv);
}
- }
-
- // set the params
- if (paramType == rendering::ShaderParam::PARAM_INT)
- {
- (*params)[spv.name] = intValue;
- }
- else if (paramType == rendering::ShaderParam::PARAM_FLOAT)
- {
- (*params)[spv.name] = floatValue;
- }
- else if (paramType == rendering::ShaderParam::PARAM_INT_BUFFER ||
- paramType == rendering::ShaderParam::PARAM_FLOAT_BUFFER)
- {
- (*params)[spv.name].InitializeBuffer(floatArrayValue.size());
- float *fv = &floatArrayValue[0];
- (*params)[spv.name].UpdateBuffer(fv);
}
}
this->shaderParams.clear();