Skip to content

Commit

Permalink
New shadow tuning parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Jul 2, 2023
1 parent 01787e4 commit 2278da0
Show file tree
Hide file tree
Showing 6 changed files with 21 additions and 2 deletions.
1 change: 1 addition & 0 deletions doc/source/doxygen-docs/changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
- Changes in libraries:
- \ref mrpt_opengl_grp
- Move the parameter eyeDistance2lightShadowExtension from TRenderMatrices to mrpt::opengl::TLightParameters so it can be changed from user code (ABI change).
- New parameter mrpt::opengl::TLightParameters::minimum_shadow_map_extension_ratio
- BUG FIXES:
- pymrpt was not automatically built when invoking the python tests using `make test_legacy`.

Expand Down
9 changes: 9 additions & 0 deletions libs/opengl/include/mrpt/opengl/TLightParameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,15 @@ struct TLightParameters
*/
double eyeDistance2lightShadowExtension = 2.0;

/** Minimum extension (in [0,1] ratio of the light distance) of the shadow
* map square ortho frustum. Should be roughly the maximum area of the
* largest room for indoor environments to ensure no missing shadows in
* distant areas.
*
* \note (New in MRPT 2.10.0)
*/
float minimum_shadow_map_extension_ratio = 0.03f;

void writeToStream(mrpt::serialization::CArchive& out) const;
void readFromStream(mrpt::serialization::CArchive& in);

Expand Down
7 changes: 5 additions & 2 deletions libs/opengl/src/TLightParameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ void TLightParameters::writeToStream(mrpt::serialization::CArchive& out) const

out << diffuse << ambient << specular << direction << color;
out << shadow_bias << shadow_bias_cam2frag << shadow_bias_normal; // v2
out << eyeDistance2lightShadowExtension; // v3
out << eyeDistance2lightShadowExtension
<< minimum_shadow_map_extension_ratio; // v3
}

void TLightParameters::readFromStream(mrpt::serialization::CArchive& in)
Expand All @@ -49,7 +50,9 @@ void TLightParameters::readFromStream(mrpt::serialization::CArchive& in)
in >> diffuse >> ambient >> specular >> direction >> color;
if (version >= 2)
in >> shadow_bias >> shadow_bias_cam2frag >> shadow_bias_normal;
if (version >= 3) in >> eyeDistance2lightShadowExtension;
if (version >= 3)
in >> eyeDistance2lightShadowExtension >>
minimum_shadow_map_extension_ratio;
break;
default: MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
};
Expand Down
4 changes: 4 additions & 0 deletions libs/opengl/src/TRenderMatrices.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,10 @@ void TRenderMatrices::computeLightProjectionMatrix(
m_last_light_z_far = zmax;

float dist = eyeDistance * lp.eyeDistance2lightShadowExtension;

// Ensure dist is not too small:
mrpt::keep_max(dist, zmax * lp.minimum_shadow_map_extension_ratio);

light_p = OrthoProjectionMatrix(-dist, dist, -dist, dist, zmin, zmax);

// "up" vector from elevation:
Expand Down
1 change: 1 addition & 0 deletions python/src/mrpt/opengl/DefaultShaders.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ void bind_mrpt_opengl_DefaultShaders(std::function< pybind11::module &(std::stri
cl.def_readwrite("shadow_bias_cam2frag", &mrpt::opengl::TLightParameters::shadow_bias_cam2frag);
cl.def_readwrite("shadow_bias_normal", &mrpt::opengl::TLightParameters::shadow_bias_normal);
cl.def_readwrite("eyeDistance2lightShadowExtension", &mrpt::opengl::TLightParameters::eyeDistance2lightShadowExtension);
cl.def_readwrite("minimum_shadow_map_extension_ratio", &mrpt::opengl::TLightParameters::minimum_shadow_map_extension_ratio);
cl.def("writeToStream", (void (mrpt::opengl::TLightParameters::*)(class mrpt::serialization::CArchive &) const) &mrpt::opengl::TLightParameters::writeToStream, "C++: mrpt::opengl::TLightParameters::writeToStream(class mrpt::serialization::CArchive &) const --> void", pybind11::arg("out"));
cl.def("readFromStream", (void (mrpt::opengl::TLightParameters::*)(class mrpt::serialization::CArchive &)) &mrpt::opengl::TLightParameters::readFromStream, "C++: mrpt::opengl::TLightParameters::readFromStream(class mrpt::serialization::CArchive &) --> void", pybind11::arg("in"));
cl.def("assign", (struct mrpt::opengl::TLightParameters & (mrpt::opengl::TLightParameters::*)(const struct mrpt::opengl::TLightParameters &)) &mrpt::opengl::TLightParameters::operator=, "C++: mrpt::opengl::TLightParameters::operator=(const struct mrpt::opengl::TLightParameters &) --> struct mrpt::opengl::TLightParameters &", pybind11::return_value_policy::automatic, pybind11::arg(""));
Expand Down
1 change: 1 addition & 0 deletions python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -3606,6 +3606,7 @@ class TLightParameters:
diffuse: float
direction: Any
eyeDistance2lightShadowExtension: float
minimum_shadow_map_extension_ratio: float
shadow_bias: float
shadow_bias_cam2frag: float
shadow_bias_normal: float
Expand Down

0 comments on commit 2278da0

Please sign in to comment.