Skip to content

Commit

Permalink
Point light shadows (#3051)
Browse files Browse the repository at this point in the history
* Added point light textures

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

* Added point light shadow camera setup

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

* Fixed frustum for point light shadow cube map

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

* Update gazebo/rendering/PointLightShadowCameraSetup.cc

Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>

* Added code suggestions

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

* Added newline to end of file

* Added code suggestion

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

* Uncommented parameter

* Point lights now cast shadows, expect true for tests

* Fixed OGRE errors

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

* Commented out unused parameter warning

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

* Added code suggestions

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

* remove unused variable

Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Co-authored-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
3 people authored Dec 9, 2021
1 parent 5dffe8c commit 505297a
Show file tree
Hide file tree
Showing 13 changed files with 585 additions and 7 deletions.
1 change: 1 addition & 0 deletions gazebo/rendering/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ set (sources
OrbitViewController.cc
OriginVisual.cc
OrthoViewController.cc
PointLightShadowCameraSetup.cc
Projector.cc
RayQuery.cc
RenderEngine.cc
Expand Down
15 changes: 14 additions & 1 deletion gazebo/rendering/Light.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include "gazebo/rendering/Visual.hh"
#include "gazebo/rendering/Light.hh"
#include "gazebo/rendering/LightPrivate.hh"
#include "gazebo/rendering/PointLightShadowCameraSetup.hh"
#include "gazebo/rendering/RTShaderSystem.hh"

using namespace gazebo;
Expand Down Expand Up @@ -594,9 +595,21 @@ void Light::SetCastShadows(const bool _cast)
RTShaderSystem::Instance()->UpdateShadows();
}
}
else if (this->dataPtr->light->getType() == Ogre::Light::LT_POINT)
{
// use different shadow camera for point light
this->dataPtr->light->setCastShadows(_cast);
if (_cast && this->dataPtr->shadowCameraSetup.isNull())
{
this->dataPtr->shadowCameraSetup =
Ogre::ShadowCameraSetupPtr(new PointLightShadowCameraSetup());
this->dataPtr->light->setCustomShadowCameraSetup(
this->dataPtr->shadowCameraSetup);
RTShaderSystem::Instance()->UpdateShadows();
}
}
else
{
// todo(anyone) make point light casts shadows
this->dataPtr->light->setCastShadows(false);
}
}
Expand Down
109 changes: 109 additions & 0 deletions gazebo/rendering/PointLightShadowCameraSetup.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
/*
* 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.
*
*/

// Code in this file has been adapted from Ogre's OgreShadowCameraSetup.
// The original Ogre's licence and copyright headers are copied below:

/*
-----------------------------------------------------------------------------
This source file is part of OGRE
(Object-oriented Graphics Rendering Engine)
For the latest info, see http://www.ogre3d.org/
Copyright (c) 2000-2014 Torus Knot Software Ltd
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
-----------------------------------------------------------------------------
*/

#include "gazebo/rendering/PointLightShadowCameraSetup.hh"
#include "gazebo/rendering/ogre_gazebo.h"

using namespace gazebo;
using namespace rendering;

//////////////////////////////////////////////////
PointLightShadowCameraSetup::PointLightShadowCameraSetup()
{
}

//////////////////////////////////////////////////
PointLightShadowCameraSetup::~PointLightShadowCameraSetup()
{
}

//////////////////////////////////////////////////
void PointLightShadowCameraSetup::getShadowCamera(
const Ogre::SceneManager */*_sm*/, const Ogre::Camera *_cam,
const Ogre::Viewport */*_vp*/, const Ogre::Light *_light,
Ogre::Camera *_texCam, size_t _iteration) const
{
Ogre::Vector3 pos, dir;

// reset custom view / projection matrix in case already set
_texCam->setCustomViewMatrix(false);
_texCam->setCustomProjectionMatrix(false);
_texCam->setNearClipDistance(_light->_deriveShadowNearClipDistance(_cam));
_texCam->setFarClipDistance(_light->_deriveShadowFarClipDistance(_cam));

_texCam->setProjectionType(Ogre::PT_PERSPECTIVE);

// theoretically set x to +-0.25 for accuracy
// decrease x for quality of shadows
float x = 0.18f;
_texCam->setFrustumExtents(-x, x, x, -x);

// set shadow cube map depending on the iteration
switch (_iteration) {
case 0:
_texCam->lookAt(_texCam->getPosition() + Ogre::Vector3(1, 0, 0));
break;
case 1:
_texCam->lookAt(_texCam->getPosition() + Ogre::Vector3(-1, 0, 0));
break;
case 2:
_texCam->lookAt(_texCam->getPosition() + Ogre::Vector3(0, 1, 0));
break;
case 3:
_texCam->lookAt(_texCam->getPosition() + Ogre::Vector3(0, -1, 0));
break;
case 4:
_texCam->lookAt(_texCam->getPosition() + Ogre::Vector3(0, 0, 1));
break;
case 5:
_texCam->lookAt(_texCam->getPosition() + Ogre::Vector3(0, 0, -1));
break;
default:
break;
}
}
48 changes: 48 additions & 0 deletions gazebo/rendering/PointLightShadowCameraSetup.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
/*
* 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.
*
*/

#ifndef GAZEBO_RENDERING_POINTLIGHTSHADOWCAMERASETUP_HH_
#define GAZEBO_RENDERING_POINTLIGHTSHADOWCAMERASETUP_HH_

#include "gazebo/rendering/ogre_gazebo.h"

#include "gazebo/util/system.hh"

namespace gazebo
{
namespace rendering
{
class GAZEBO_VISIBLE PointLightShadowCameraSetup
: public Ogre::DefaultShadowCameraSetup
{
/// \brief Constructor
public: PointLightShadowCameraSetup();

/// \brief Destructor
public: ~PointLightShadowCameraSetup();

/// \brief Returns a shadow camera for a point light
/// \sa FocusedShadowCameraSetup::getShadowCamera()
public: virtual void getShadowCamera(const Ogre::SceneManager *_sm,
const Ogre::Camera *_cam, const Ogre::Viewport *_vp,
const Ogre::Light *_light, Ogre::Camera *_texCam, size_t _iteration)
const override;
};
}
}

#endif
13 changes: 10 additions & 3 deletions gazebo/rendering/RTShaderSystem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -728,6 +728,7 @@ void RTShaderSystem::UpdateShadows(ScenePtr _scene)
// point: not working yet
unsigned int dirLightCount = 1u;
unsigned int spotLightCount = 0u;
unsigned int pointLightCount = 0u;
for (unsigned int i = 0; i < _scene->LightCount(); ++i)
{
LightPtr light = _scene->LightByIndex(i);
Expand All @@ -737,6 +738,9 @@ void RTShaderSystem::UpdateShadows(ScenePtr _scene)

if (light->Type() == "spot")
spotLightCount++;

if (light->Type() == "point")
pointLightCount++;
}

// 3 textures per directional light
Expand All @@ -746,12 +750,14 @@ void RTShaderSystem::UpdateShadows(ScenePtr _scene)
sceneMgr->setShadowTextureCountPerLightType(Ogre::Light::LT_SPOTLIGHT, 1);

// \todo(anyone) make point light shadows work
sceneMgr->setShadowTextureCountPerLightType(Ogre::Light::LT_POINT, 0);
sceneMgr->setShadowTextureCountPerLightType(Ogre::Light::LT_POINT, 6);

// \todo(anyone) include point light shadows when it is working
unsigned int dirShadowCount = 3 * dirLightCount;
unsigned int spotShadowCount = spotLightCount;
sceneMgr->setShadowTextureCount(dirShadowCount + spotShadowCount);
unsigned int pointShadowCount = 6 * pointLightCount;
sceneMgr->setShadowTextureCount(dirShadowCount + spotShadowCount +
pointShadowCount);

unsigned int texSize = this->dataPtr->shadowTextureSize;
#if defined(__APPLE__)
Expand All @@ -771,7 +777,8 @@ void RTShaderSystem::UpdateShadows(ScenePtr _scene)
// vec4 texture(sampler2D, vec2, [float]).
// NVidia, AMD, and Intel all take this as a cue to provide "hardware PCF",
// a driver hack that softens shadow edges with 4-sample interpolation.
for (size_t i = 0u; i < dirShadowCount + spotShadowCount; ++i)
for (size_t i = 0u; i < dirShadowCount + spotShadowCount + pointShadowCount;
++i)
{
const Ogre::TexturePtr tex = sceneMgr->getShadowTexture(i);
// This will fail if not using OpenGL as the rendering backend.
Expand Down
3 changes: 1 addition & 2 deletions gazebo/rendering/RenderingLight_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -127,8 +127,7 @@ TEST_F(Light_TEST, CastShadows)
msg.set_cast_shadows(true);
pointLight->LoadFromMsg(msg);
EXPECT_EQ(pointLight->LightType(), "point");
// issue #2083: point light does not cast shadows
EXPECT_FALSE(pointLight->CastShadows());
EXPECT_TRUE(pointLight->CastShadows());
scene->RemoveLight(pointLight);
pointLight.reset();
}
Expand Down
2 changes: 2 additions & 0 deletions media/materials/programs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@ perpixel_fp.glsl
perpixel_vp.glsl
plain_color_fs.glsl
plain_color_vs.glsl
point_light_shadow_demo_fp.glsl
point_light_shadow_demo_vp.glsl
point_receiver_fp.glsl
point_receiver_vp.glsl
projector.frag
Expand Down
62 changes: 62 additions & 0 deletions media/materials/programs/point_light_shadow_demo_fp.glsl
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
#version 130

uniform sampler2DShadow shadowMap0;
uniform sampler2DShadow shadowMap1;
uniform sampler2DShadow shadowMap2;
uniform sampler2DShadow shadowMap3;
uniform sampler2DShadow shadowMap4;
uniform sampler2DShadow shadowMap5;

varying vec4 lightSpacePos0;
varying vec4 lightSpacePos1;
varying vec4 lightSpacePos2;
varying vec4 lightSpacePos3;
varying vec4 lightSpacePos4;
varying vec4 lightSpacePos5;

varying vec4 worldPos;

//------------------------------------------------------------------------------
float ShadowSimple(in sampler2DShadow shadowMap, in vec4 shadowMapPos)
{
// perform perspective divide
vec3 shadowMapUV = shadowMapPos.xyz / shadowMapPos.w;

if (shadowMapUV.z < 0.0 || shadowMapUV.z > 1.0)
return 0.0;
if (shadowMapUV.x < 0.0 || shadowMapUV.x > 1.0)
return 0.0;
if (shadowMapUV.y < 0.0 || shadowMapUV.y > 1.0)
return 0.0;

// get closest depth value from light's perspective
float closestDepth = texture(shadowMap, shadowMapUV);

// get depth of current fragment from light's perspective
float currentDepth = shadowMapUV.z;

// check whether current frag pos is in shadow
float shadow = currentDepth > closestDepth ? 1.0 : 0.0;

return shadow;
}

void main()
{
float f = 0.0f;

vec4 outColor = vec4(1.0, 0.0, 0.0, 1.0);

// grey shadows
f += ShadowSimple(shadowMap0, lightSpacePos0);
f += ShadowSimple(shadowMap1, lightSpacePos1);
f += ShadowSimple(shadowMap2, lightSpacePos2);
f += ShadowSimple(shadowMap3, lightSpacePos3);
f += ShadowSimple(shadowMap4, lightSpacePos4);
f += ShadowSimple(shadowMap5, lightSpacePos5);
f = clamp(f, 0.0f, 1.0f);
if (f > 0.0f)
outColor = vec4(0.0, 0.0, 0.0, 1.0);

gl_FragColor = outColor;
}
34 changes: 34 additions & 0 deletions media/materials/programs/point_light_shadow_demo_vp.glsl
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#version 120

uniform mat4 worldMatrix;
uniform mat4 worldViewMatrix;
uniform mat4 viewProjMatrix;

uniform mat4 texViewProjMatrix0;
uniform mat4 texViewProjMatrix1;
uniform mat4 texViewProjMatrix2;
uniform mat4 texViewProjMatrix3;
uniform mat4 texViewProjMatrix4;
uniform mat4 texViewProjMatrix5;
varying vec4 lightSpacePos0;
varying vec4 lightSpacePos1;
varying vec4 lightSpacePos2;
varying vec4 lightSpacePos3;
varying vec4 lightSpacePos4;
varying vec4 lightSpacePos5;

varying vec4 worldPos;

void main()
{
worldPos = worldMatrix * gl_Vertex;
gl_Position = viewProjMatrix * worldPos;

lightSpacePos0 = texViewProjMatrix0 * worldPos;
lightSpacePos1 = texViewProjMatrix1 * worldPos;
lightSpacePos2 = texViewProjMatrix2 * worldPos;
lightSpacePos3 = texViewProjMatrix3 * worldPos;
lightSpacePos4 = texViewProjMatrix4 * worldPos;
lightSpacePos5 = texViewProjMatrix5 * worldPos;
}

1 change: 1 addition & 0 deletions media/materials/scripts/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ noise.compositor
oculus.material
perpixel.program
picker.material
point_light_shadow_demo.material
ShadowCaster.material
shadow_caster.program
shadow_caster_ignore_heightmap.program
Expand Down
Loading

0 comments on commit 505297a

Please sign in to comment.