Skip to content
This repository has been archived by the owner on Feb 3, 2025. It is now read-only.

Commit

Permalink
Custom shadow caster materials (#3048)
Browse files Browse the repository at this point in the history
This allows the shadow caster material name to be specified
in a `<ignition:shadow_caster_material_name/>` SDFormat
element under `<scene/>`. To avoid breaking ABI, this
data is not added to the `scene.proto` message, but
instead is exposed through an ign-transport service named
`/shadow_caster_material_name` by `physics::World`.

An example material is provided that avoids heightmap
self-shadowing and is used in a test.

Signed-off-by: William Lew <WilliamMilesLew@gmail.com>

* Improve console messages
* Remove input parameter from service

Signed-off-by: Steven Peters <scpeters@openrobotics.org>
Co-authored-by: Steven Peters <scpeters@openrobotics.org>
  • Loading branch information
WilliamLewww and scpeters authored Aug 12, 2021
1 parent 88afb77 commit 42f7e48
Show file tree
Hide file tree
Showing 15 changed files with 469 additions and 2 deletions.
27 changes: 27 additions & 0 deletions gazebo/physics/World.cc
Original file line number Diff line number Diff line change
Expand Up @@ -217,6 +217,18 @@ void World::Load(sdf::ElementPtr _sdf)
msgs::SceneFromSDF(this->dataPtr->sdf->GetElement("scene")));
this->dataPtr->sceneMsg.set_name(this->Name());

if (this->dataPtr->sdf->GetElement("scene")->
HasElement("ignition:shadow_caster_material_name"))
{
this->dataPtr->shadowCasterMaterialName =
this->dataPtr->sdf->GetElement("scene")->
Get<std::string>("ignition:shadow_caster_material_name");
}
else
{
this->dataPtr->shadowCasterMaterialName = "Gazebo/shadow_caster";
}

// The period at which messages are processed
this->dataPtr->processMsgsPeriod = common::Time(0, 200000000);

Expand Down Expand Up @@ -284,6 +296,14 @@ void World::Load(sdf::ElementPtr _sdf)
<< std::endl;
}

std::string shadowCasterService("/shadow_caster_material_name");
if (!this->dataPtr->ignNode.Advertise(shadowCasterService,
&World::ShadowCasterService, this))
{
gzerr << "Error advertising service [" << shadowCasterService << "]"
<< std::endl;
}

// This should come before loading of entities
sdf::ElementPtr physicsElem = this->dataPtr->sdf->GetElement("physics");

Expand Down Expand Up @@ -3337,3 +3357,10 @@ bool World::PluginInfoService(const ignition::msgs::StringMsg &_req,

return false;
}

//////////////////////////////////////////////////
bool World::ShadowCasterService(ignition::msgs::StringMsg &_res)
{
_res.set_data(this->dataPtr->shadowCasterMaterialName.c_str());
return true;
}
5 changes: 5 additions & 0 deletions gazebo/physics/World.hh
Original file line number Diff line number Diff line change
Expand Up @@ -651,6 +651,11 @@ namespace gazebo
private: bool PluginInfoService(const ignition::msgs::StringMsg &_request,
ignition::msgs::Plugin_V &_plugins);

/// \brief Callback for "<this_name>/shadow_caster_material_name" service.
/// \param[out] _response Message containing shadow caster material name
/// \return True if the info was successfully obtained.
private: bool ShadowCasterService(ignition::msgs::StringMsg &_response);

/// \internal
/// \brief Private data pointer.
private: std::unique_ptr<WorldPrivate> dataPtr;
Expand Down
3 changes: 3 additions & 0 deletions gazebo/physics/WorldPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -385,6 +385,9 @@ namespace gazebo

/// \brief SDF World DOM object
public: std::unique_ptr<sdf::World> worldSDFDom;

/// \brief Shadow caster material name from scene SDF
public: std::string shadowCasterMaterialName;
};
}
}
Expand Down
5 changes: 3 additions & 2 deletions gazebo/rendering/RTShaderSystem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -796,8 +796,9 @@ void RTShaderSystem::UpdateShadows(ScenePtr _scene)
// sceneMgr->setShadowTextureCasterMaterial("PSSM/shadow_caster");
#if OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR >= 11
sceneMgr->setShadowTextureCasterMaterial(
Ogre::MaterialManager::getSingleton().getByName("Gazebo/shadow_caster"));
Ogre::MaterialManager::getSingleton().getByName(
_scene->ShadowCasterMaterialName()));
#else
sceneMgr->setShadowTextureCasterMaterial("Gazebo/shadow_caster");
sceneMgr->setShadowTextureCasterMaterial(_scene->ShadowCasterMaterialName());
#endif
}
26 changes: 26 additions & 0 deletions gazebo/rendering/Scene.cc
Original file line number Diff line number Diff line change
Expand Up @@ -206,6 +206,26 @@ Scene::Scene(const std::string &_name, const bool _enableVisualizations,

this->dataPtr->sceneSimTimePosesApplied = common::Time();
this->dataPtr->sceneSimTimePosesReceived = common::Time();

// Get shadow caster material name from physics::World
ignition::transport::Node node;
ignition::msgs::StringMsg rep;
const std::string serviceName = "/shadow_caster_material_name";
bool result;
unsigned int timeout = 5000;
bool executed = node.Request(serviceName,
timeout, rep, result);
if (executed)
{
if (result)
this->dataPtr->shadowCasterMaterialName = rep.data();
else
gzerr << "Service call[" << serviceName << "] failed" << std::endl;
}
else
{
gzerr << "Service call[" << serviceName << "] timed out" << std::endl;
}
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -3285,6 +3305,12 @@ unsigned int Scene::ShadowTextureSize() const
return this->dataPtr->shadowTextureSize;
}

/////////////////////////////////////////////////
std::string Scene::ShadowCasterMaterialName() const
{
return this->dataPtr->shadowCasterMaterialName;
}

/////////////////////////////////////////////////
void Scene::AddVisual(VisualPtr _vis)
{
Expand Down
6 changes: 6 additions & 0 deletions gazebo/rendering/Scene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,7 @@ namespace gazebo
/// \brief Process all received messages.
public: void PreRender();


/// \brief Wait until a render request occurs
/// \param[in] _timeoutsec timeout expressed in seconds
/// \return True if timeout was NOT met
Expand Down Expand Up @@ -380,6 +381,7 @@ namespace gazebo
const ignition::math::Vector3d &_end,
const std::string &_name);


/// \brief Set the fog parameters.
/// \param[in] _type Type of fog: "linear", "exp", or "exp2".
/// \param[in] _color Color of the fog.
Expand Down Expand Up @@ -418,6 +420,10 @@ namespace gazebo
/// \return Size of the shadow texture. The default size is 1024.
public: unsigned int ShadowTextureSize() const;

/// \brief Get the shadow caster material name
/// \return Name of the shadow caster material
public: std::string ShadowCasterMaterialName() const;

/// \brief Add a visual to the scene
/// \param[in] _vis Visual to add.
public: void AddVisual(VisualPtr _vis);
Expand Down
3 changes: 3 additions & 0 deletions gazebo/rendering/ScenePrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -376,6 +376,9 @@ namespace gazebo
/// \brief State of each layer where key is the layer id, and value is
/// the layer's visibility.
public: std::map<int32_t, bool> layerState;

/// \brief Shadow caster material name
public: std::string shadowCasterMaterialName;
};
}
}
Expand Down
1 change: 1 addition & 0 deletions media/materials/programs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ point_receiver_vp.glsl
projector.frag
projector.vert
shadow_caster_fp.glsl
shadow_caster_ignore_heightmap_fp.glsl
shadow_caster_vp.glsl
StdQuad_vp.glsl
spotlight_shadow_demo_fp.glsl
Expand Down
25 changes: 25 additions & 0 deletions media/materials/programs/shadow_caster_ignore_heightmap_fp.glsl
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
uniform vec4 camera_position;
uniform mat4 world_matrix;

// uniform vec4 depth_range;
varying vec4 vertex_depth;

void main()
{
float depth = (vertex_depth.z) / vertex_depth.w;

// Linear
// float depth = (vertex_depth.z - depth_range.x) / depth_range.w;

vec4 magicVector1 = vec4(1.0, 0.0, 0.0, 0.0);
vec4 magicVector2 = vec4(0.0, 1.0, 0.0, 0.0);
vec4 magicVector3 = vec4(0.0, 0.0, 1.0, 0.0);

bool matchingVectors = (magicVector1 == world_matrix[0] && magicVector2 == world_matrix[1] && magicVector3 == world_matrix[2]);

if (length(camera_position.xyz) == 0 && matchingVectors) {
depth = 1.0;
}

gl_FragColor = vec4(depth, depth, depth, 1.0);
}
1 change: 1 addition & 0 deletions media/materials/scripts/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ perpixel.program
picker.material
ShadowCaster.material
shadow_caster.program
shadow_caster_ignore_heightmap.program
ShadowCaster.program
spotlight_shadow_demo.material
ssao.compositor
Expand Down
41 changes: 41 additions & 0 deletions media/materials/scripts/shadow_caster_ignore_heightmap.program
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
vertex_program shadow_caster_vp_glsl glsl
{
source shadow_caster_vp.glsl

default_params
{
param_named_auto world_view_proj_mat worldviewproj_matrix
param_named_auto texel_offsets texel_offsets
}
}

fragment_program shadow_caster_ignore_heightmap_fp_glsl glsl
{
source shadow_caster_ignore_heightmap_fp.glsl

default_params
{
param_named_auto camera_position camera_position
param_named_auto world_matrix world_matrix
// param_named_auto depth_range shadow_scene_depth_range
}
}


material Gazebo/shadow_caster_ignore_heightmap
{
technique
{
// all this will do is write depth and depth*depth to red and green
pass
{
vertex_program_ref shadow_caster_vp_glsl
{
}

fragment_program_ref shadow_caster_ignore_heightmap_fp_glsl
{
}
}
}
}
7 changes: 7 additions & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,13 @@ if (NOT WIN32)
)
endif()

if (NOT APPLE)
set(tests
${tests}
custom_shadow_caster.cc
)
endif()

if (HAVE_GTS)
set(tests
${tests}
Expand Down
Loading

0 comments on commit 42f7e48

Please sign in to comment.