From 2278da0383922035d32005c22b72ed2484bfc275 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 3 Jul 2023 01:22:26 +0200 Subject: [PATCH] New shadow tuning parameter --- doc/source/doxygen-docs/changelog.md | 1 + libs/opengl/include/mrpt/opengl/TLightParameters.h | 9 +++++++++ libs/opengl/src/TLightParameters.cpp | 7 +++++-- libs/opengl/src/TRenderMatrices.cpp | 4 ++++ python/src/mrpt/opengl/DefaultShaders.cpp | 1 + python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi | 1 + 6 files changed, 21 insertions(+), 2 deletions(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 91ff91fc83..8d8f0e73a8 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -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`. diff --git a/libs/opengl/include/mrpt/opengl/TLightParameters.h b/libs/opengl/include/mrpt/opengl/TLightParameters.h index 8d67973ac1..b2cb170bba 100644 --- a/libs/opengl/include/mrpt/opengl/TLightParameters.h +++ b/libs/opengl/include/mrpt/opengl/TLightParameters.h @@ -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); diff --git a/libs/opengl/src/TLightParameters.cpp b/libs/opengl/src/TLightParameters.cpp index 85e96da20c..6dd23459b4 100644 --- a/libs/opengl/src/TLightParameters.cpp +++ b/libs/opengl/src/TLightParameters.cpp @@ -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) @@ -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); }; diff --git a/libs/opengl/src/TRenderMatrices.cpp b/libs/opengl/src/TRenderMatrices.cpp index 9ee8bfd717..a17a10d669 100644 --- a/libs/opengl/src/TRenderMatrices.cpp +++ b/libs/opengl/src/TRenderMatrices.cpp @@ -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: diff --git a/python/src/mrpt/opengl/DefaultShaders.cpp b/python/src/mrpt/opengl/DefaultShaders.cpp index 40e71d1c66..df85da7cff 100644 --- a/python/src/mrpt/opengl/DefaultShaders.cpp +++ b/python/src/mrpt/opengl/DefaultShaders.cpp @@ -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("")); diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi index dbd2f10ab9..8abd014c74 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi @@ -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