From acdfd09a05ac4e3032eb9ccb9b14fdb9caa2abcd Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sun, 18 Jul 2021 18:04:10 -0300 Subject: [PATCH 1/2] Use clipping distance for minimum LIDAR distance Using Hlms custom pieces and a listener to implement it See changes to Ogre2GpuRays::Render for usage Update ogre2/src/media/Hlms/Pbs/GLSL/VertexShader_vs.glsl to latest upstream version Signed-off-by: Matias N. Goldberg --- .../rendering/ogre2/Ogre2RenderEngine.hh | 4 + ogre2/src/Ogre2GpuRays.cc | 8 ++ ogre2/src/Ogre2IgnHlmsCustomizations.cc | 121 ++++++++++++++++++ ogre2/src/Ogre2IgnHlmsCustomizations.hh | 118 +++++++++++++++++ ogre2/src/Ogre2RenderEngine.cc | 20 +++ .../Ignition/IgnCustomStructs_piece_all.any | 11 ++ .../src/media/Hlms/Ignition/Ign_piece_vs.any | 15 +++ .../media/Hlms/Pbs/GLSL/VertexShader_vs.glsl | 4 +- 8 files changed, 299 insertions(+), 2 deletions(-) create mode 100644 ogre2/src/Ogre2IgnHlmsCustomizations.cc create mode 100644 ogre2/src/Ogre2IgnHlmsCustomizations.hh create mode 100644 ogre2/src/media/Hlms/Ignition/IgnCustomStructs_piece_all.any create mode 100644 ogre2/src/media/Hlms/Ignition/Ign_piece_vs.any diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh index 677548f98..d61a2101c 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh @@ -48,6 +48,7 @@ namespace ignition // // forward declaration class Ogre2RenderEnginePrivate; + class Ogre2IgnHlmsCustomizations; /// \brief Plugin for loading ogre render engine class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2RenderEnginePlugin : @@ -163,6 +164,9 @@ namespace ignition /// \return a list of FSAA levels public: std::vector FSAALevels() const; + /// \brief Retrieves Hlms customizations for tweaking them + public: Ogre2IgnHlmsCustomizations& HlmsCustomizations(); + /// \internal /// \brief Get a pointer to the Ogre overlay system. /// \return Pointer to the ogre overlay system. diff --git a/ogre2/src/Ogre2GpuRays.cc b/ogre2/src/Ogre2GpuRays.cc index 051ee4e05..e8f9ae240 100644 --- a/ogre2/src/Ogre2GpuRays.cc +++ b/ogre2/src/Ogre2GpuRays.cc @@ -34,6 +34,7 @@ #include "ignition/rendering/ogre2/Ogre2Sensor.hh" #include "ignition/rendering/ogre2/Ogre2Visual.hh" +#include "Ogre2IgnHlmsCustomizations.hh" #include "Ogre2ParticleNoiseListener.hh" namespace ignition @@ -1090,8 +1091,15 @@ void Ogre2GpuRays::UpdateRenderTarget2ndPass() ////////////////////////////////////////////////// void Ogre2GpuRays::Render() { + auto engine = Ogre2RenderEngine::Instance(); + Ogre2IgnHlmsCustomizations &hlmsCustomizations = + engine->HlmsCustomizations(); + + hlmsCustomizations.minDistanceClip = + static_cast(this->NearClipPlane()); this->UpdateRenderTarget1stPass(); this->UpdateRenderTarget2ndPass(); + hlmsCustomizations.minDistanceClip = -1; } ////////////////////////////////////////////////// diff --git a/ogre2/src/Ogre2IgnHlmsCustomizations.cc b/ogre2/src/Ogre2IgnHlmsCustomizations.cc new file mode 100644 index 000000000..251c927dd --- /dev/null +++ b/ogre2/src/Ogre2IgnHlmsCustomizations.cc @@ -0,0 +1,121 @@ +/* + * 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. + * +*/ + +#include "Ogre2IgnHlmsCustomizations.hh" + +#ifdef _MSC_VER + #pragma warning(push, 0) +#endif +#include +#include +#include +#include +#include +#ifdef _MSC_VER + #pragma warning(pop) +#endif + +using namespace ignition; +using namespace rendering; + +////////////////////////////////////////////////// +void Ogre2IgnHlmsCustomizations::preparePassHash( + const Ogre::CompositorShadowNode */*_shadowNode*/, + bool _casterPass, bool /*_dualParaboloid*/, + Ogre::SceneManager */*_sceneManager*/, + Ogre::Hlms *_hlms) +{ + this->needsWorldPos = false; + if (!_casterPass && this->MinDistanceClipEnabled()) + { + const Ogre::int32 numClipPlanes = + _hlms->_getProperty("hlms_pso_clip_distances"); + _hlms->_setProperty( "ign_spherical_clip_min_distance", 1 ); + _hlms->_setProperty( "ign_spherical_clip_idx", numClipPlanes ); + _hlms->_setProperty( "hlms_pso_clip_distances", numClipPlanes + 1 ); + + if (_hlms->getType() == Ogre::HLMS_UNLIT) + { + if (_hlms->_getProperty("hlms_global_clip_planes") == 0) + { + this->needsWorldPos = true; + _hlms->_setProperty( "ign_spherical_clip_needs_worldPos", 1 ); + } + } + } +} + +////////////////////////////////////////////////// +Ogre::uint32 Ogre2IgnHlmsCustomizations::getPassBufferSize( + const Ogre::CompositorShadowNode */*_shadowNode*/, + bool _casterPass, bool /*_dualParaboloid*/, + Ogre::SceneManager */*_sceneManager*/) const +{ + if (_casterPass || !this->MinDistanceClipEnabled()) + return 0u; + + Ogre::uint32 bufferSize = sizeof(float) * 4u; + if (this->needsWorldPos) + bufferSize += sizeof(float) * 16u; + + return bufferSize; +} + +////////////////////////////////////////////////// +float* Ogre2IgnHlmsCustomizations::preparePassBuffer( + const Ogre::CompositorShadowNode */*_shadowNode*/, + bool _casterPass, bool /*_dualParaboloid*/, + Ogre::SceneManager *_sceneManager, + float *_passBufferPtr) +{ + if (!_casterPass && this->MinDistanceClipEnabled()) + { + Ogre::Camera *camera = _sceneManager->getCameraInProgress(); + const Ogre::Vector3 &camPos = camera->getDerivedPosition(); + + // float4 ignMinClipDistance_ignCameraPos + *_passBufferPtr++ = this->minDistanceClip; + *_passBufferPtr++ = camPos.x; + *_passBufferPtr++ = camPos.y; + *_passBufferPtr++ = camPos.z; + + if (this->needsWorldPos) + { + // TODO(dark_sylinc): Modify Ogre to access HlmsUnlit::mPreparedPass + // so we get the view matrix that's going to be used instead of + // recalculating everything again (which can get complex if VR is + // being used) + const Ogre::RenderTarget *renderTarget = + _sceneManager->getCurrentViewport()->getTarget(); + Ogre::Matrix4 projectionMatrix = + camera->getProjectionMatrixWithRSDepth(); + if( renderTarget->requiresTextureFlipping() ) + { + projectionMatrix[1][0] = -projectionMatrix[1][0]; + projectionMatrix[1][1] = -projectionMatrix[1][1]; + projectionMatrix[1][2] = -projectionMatrix[1][2]; + projectionMatrix[1][3] = -projectionMatrix[1][3]; + } + + Ogre::Matrix4 invViewProj = (projectionMatrix * + camera->getViewMatrix(true)).inverse(); + for (size_t i = 0; i < 16u; ++i) + *_passBufferPtr++ = static_cast(invViewProj[0][i]); + } + } + return _passBufferPtr; +} diff --git a/ogre2/src/Ogre2IgnHlmsCustomizations.hh b/ogre2/src/Ogre2IgnHlmsCustomizations.hh new file mode 100644 index 000000000..474b083b6 --- /dev/null +++ b/ogre2/src/Ogre2IgnHlmsCustomizations.hh @@ -0,0 +1,118 @@ +/* + * 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 IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSCUSTOMIZATIONS_HH_ +#define IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSCUSTOMIZATIONS_HH_ + +#include "ignition/rendering/config.hh" +#include "ignition/rendering/ogre2/Export.hh" + +#ifdef _MSC_VER + #pragma warning(push, 0) +#endif +#include +#ifdef _MSC_VER + #pragma warning(pop) +#endif + +namespace ignition +{ + namespace rendering + { + inline namespace IGNITION_RENDERING_VERSION_NAMESPACE { + // + /// \brief Controls custom shader snippets of Hlms (both Pbs and Unlit): + /// + /// - Toggles them on/off + /// - Sends relevant data to the GPU buffers for shaders to use + /// + /// This listener requires Hlms to have been created with the piece data + /// files in ogre2/src/media/Hlms/Ignition registered + /// + /// \internal + /// \remark Public variables take effect immediately (i.e. for the + /// next render) + class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2IgnHlmsCustomizations final : + public Ogre::HlmsListener + { + public: + virtual ~Ogre2IgnHlmsCustomizations() = default; + + /// \brief + /// \return Returns true if spherical clipping customizations should + /// be active + public: bool MinDistanceClipEnabled() const + { + return this->minDistanceClip >= 0.0f; + } + + /// \brief Determines which custom pieces we should activate + /// \param _casterPass + /// \param _hlms + private: virtual void preparePassHash( + const Ogre::CompositorShadowNode *_shadowNode, + bool _casterPass, bool _dualParaboloid, + Ogre::SceneManager *_sceneManager, + Ogre::Hlms *_hlms) override; + + /// \brief Tells Ogre the buffer data sent to GPU should be a little + /// bigger to fit our data we need to send + /// + /// This data is sent in Ogre2IgnHlmsCustomizations::preparePassBuffer + /// \param _casterPass + /// \param _hlms + private: virtual Ogre::uint32 getPassBufferSize( + const Ogre::CompositorShadowNode *_shadowNode, + bool _casterPass, bool _dualParaboloid, + Ogre::SceneManager *_sceneManager) const override; + + /// \brief Sends our custom data to GPU buffers that our + /// pieces activated in Ogre2IgnHlmsCustomizations::preparePassHash + /// will need. + /// + /// Bytes written must not exceed what we informed in getPassBufferSize + /// \param _casterPass + /// \param _sceneManager + /// \param _passBufferPtr + /// \return The pointer where Ogre should continue appending more data + private: virtual float* preparePassBuffer( + const Ogre::CompositorShadowNode *_shadowNode, + bool _casterPass, bool _dualParaboloid, + Ogre::SceneManager *_sceneManager, + float *_passBufferPtr) override; + + /// \brief Min distance to clip geometry against in a spherical manner + /// (i.e. vertices that are too close to camera are clipped) + /// Usually this means the min lidar distance + /// + /// Regular near clip distance clips in a rectangular way, so + /// it's not enough. + /// + /// Set to a negative value to disable (0 does NOT disable it!) + /// + /// See https://github.com/ignitionrobotics/ign-rendering/pull/356 + public: float minDistanceClip = -1.0f; + + /// \brief When true, we're currently dealing with HlmsUnlit + /// where we need to define and calculate `float3 worldPos` + /// \internal + private: bool needsWorldPos = false; + }; + } + } +} +#endif diff --git a/ogre2/src/Ogre2RenderEngine.cc b/ogre2/src/Ogre2RenderEngine.cc index 6a5db7ef8..8a240e46d 100644 --- a/ogre2/src/Ogre2RenderEngine.cc +++ b/ogre2/src/Ogre2RenderEngine.cc @@ -40,6 +40,7 @@ #include "ignition/rendering/ogre2/Ogre2Scene.hh" #include "ignition/rendering/ogre2/Ogre2Storage.hh" +#include "Ogre2IgnHlmsCustomizations.hh" class ignition::rendering::Ogre2RenderEnginePrivate { @@ -49,6 +50,9 @@ class ignition::rendering::Ogre2RenderEnginePrivate /// \brief A list of supported fsaa levels public: std::vector fsaaLevels; + + /// \brief Controls Hlms customizations for both PBS and Unlit + public: ignition::rendering::Ogre2IgnHlmsCustomizations hlmsCustomizations; }; using namespace ignition; @@ -612,6 +616,10 @@ void Ogre2RenderEngine::CreateResources() Ogre::ArchiveManager &archiveManager = Ogre::ArchiveManager::getSingleton(); + Ogre::Archive *customizationsArchiveLibrary = + archiveManager.load( rootHlmsFolder + "Hlms/Ignition", "FileSystem", + true ); + { Ogre::HlmsUnlit *hlmsUnlit = 0; // Create & Register HlmsUnlit @@ -631,6 +639,8 @@ void Ogre2RenderEngine::CreateResources() ++libraryFolderPathIt; } + archiveUnlitLibraryFolders.push_back( customizationsArchiveLibrary ); + // Create and register the unlit Hlms hlmsUnlit = OGRE_NEW Ogre::HlmsUnlit(archiveUnlit, &archiveUnlitLibraryFolders); @@ -638,6 +648,7 @@ void Ogre2RenderEngine::CreateResources() // disable writting debug output to disk hlmsUnlit->setDebugOutputPath(false, false); + hlmsUnlit->setListener(&this->dataPtr->hlmsCustomizations); } { @@ -661,12 +672,15 @@ void Ogre2RenderEngine::CreateResources() ++libraryFolderPathIt; } + archivePbsLibraryFolders.push_back( customizationsArchiveLibrary ); + // Create and register hlmsPbs = OGRE_NEW Ogre::HlmsPbs(archivePbs, &archivePbsLibraryFolders); Ogre::Root::getSingleton().getHlmsManager()->registerHlms(hlmsPbs); // disable writting debug output to disk hlmsPbs->setDebugOutputPath(false, false); + hlmsPbs->setListener(&this->dataPtr->hlmsCustomizations); } } @@ -782,6 +796,12 @@ std::vector Ogre2RenderEngine::FSAALevels() const return this->dataPtr->fsaaLevels; } +///////////////////////////////////////////////// +Ogre2IgnHlmsCustomizations& Ogre2RenderEngine::HlmsCustomizations() +{ + return this->dataPtr->hlmsCustomizations; +} + ///////////////////////////////////////////////// Ogre::v1::OverlaySystem *Ogre2RenderEngine::OverlaySystem() const { diff --git a/ogre2/src/media/Hlms/Ignition/IgnCustomStructs_piece_all.any b/ogre2/src/media/Hlms/Ignition/IgnCustomStructs_piece_all.any new file mode 100644 index 000000000..5c21d621d --- /dev/null +++ b/ogre2/src/media/Hlms/Ignition/IgnCustomStructs_piece_all.any @@ -0,0 +1,11 @@ +@property( ign_spherical_clip_min_distance ) + @piece( custom_passBuffer ) + #define ignMinClipDistance ignMinClipDistance_ignCameraPos.x + #define ignCameraPos ignMinClipDistance_ignCameraPos.yzw + float4 ignMinClipDistance_ignCameraPos; + + @property( ign_spherical_clip_needs_worldPos ) + float4x4 invViewProj; + @end + @end +@end diff --git a/ogre2/src/media/Hlms/Ignition/Ign_piece_vs.any b/ogre2/src/media/Hlms/Ignition/Ign_piece_vs.any new file mode 100644 index 000000000..757b8166a --- /dev/null +++ b/ogre2/src/media/Hlms/Ignition/Ign_piece_vs.any @@ -0,0 +1,15 @@ +@property( ign_spherical_clip_min_distance ) + @piece( custom_vs_posExecution ) + @property( ign_spherical_clip_needs_worldPos ) + // Unlit didn't declare this + float3 worldPos = (gl_Position * passBuf.invViewProj).xyz; + @end + + // Ogre 2.2 should use outVs_clipDistanceN for compatibility with all + // APIs + // Rare case of geometry without normals. + gl_ClipDistance[@value(ign_spherical_clip_idx)] = + distance( worldPos.xyz, passBuf.ignCameraPos.xyz ) - + passBuf.ignMinClipDistance; + @end +@end diff --git a/ogre2/src/media/Hlms/Pbs/GLSL/VertexShader_vs.glsl b/ogre2/src/media/Hlms/Pbs/GLSL/VertexShader_vs.glsl index 5f00ee59f..feeedd932 100644 --- a/ogre2/src/media/Hlms/Pbs/GLSL/VertexShader_vs.glsl +++ b/ogre2/src/media/Hlms/Pbs/GLSL/VertexShader_vs.glsl @@ -4,8 +4,8 @@ out gl_PerVertex { vec4 gl_Position; -@property( hlms_global_clip_planes ) - float gl_ClipDistance[@value(hlms_global_clip_planes)]; +@property( hlms_pso_clip_distances ) + float gl_ClipDistance[@value(hlms_pso_clip_distances)]; @end }; From e7bcb69239f995114c6c5c85fa2e485b2f358dc0 Mon Sep 17 00:00:00 2001 From: "Matias N. Goldberg" Date: Sun, 25 Jul 2021 19:03:43 -0300 Subject: [PATCH 2/2] Add gl_ClipDistance to low level material that needed it Needs Ogre 2.1 update to actually take effect The `num_clip_distances` keyword will otherwise be ignored Signed-off-by: Matias N. Goldberg --- ogre2/src/Ogre2GpuRays.cc | 15 +++++++++++++++ .../media/materials/programs/plain_color_vs.glsl | 16 ++++++++++++++++ .../media/materials/scripts/gpu_rays.material | 3 +++ .../src/media/materials/scripts/picker.material | 3 +++ .../src/media/materials/scripts/thermal.material | 3 +++ 5 files changed, 40 insertions(+) diff --git a/ogre2/src/Ogre2GpuRays.cc b/ogre2/src/Ogre2GpuRays.cc index e8f9ae240..57dfa4df1 100644 --- a/ogre2/src/Ogre2GpuRays.cc +++ b/ogre2/src/Ogre2GpuRays.cc @@ -200,6 +200,16 @@ Ogre2LaserRetroMaterialSwitcher::Ogre2LaserRetroMaterialSwitcher( void Ogre2LaserRetroMaterialSwitcher::preRenderTargetUpdate( const Ogre::RenderTargetEvent & /*_evt*/) { + { + auto engine = Ogre2RenderEngine::Instance(); + Ogre2IgnHlmsCustomizations &hlmsCustomizations = + engine->HlmsCustomizations(); + Ogre::Pass *pass = + this->laserRetroSourceMaterial->getBestTechnique()->getPass(0u); + pass->getVertexProgramParameters()->setNamedConstant( + "ignMinClipDistance", hlmsCustomizations.minDistanceClip ); + } + // swap item to use v1 shader material // Note: keep an eye out for performance impact on switching materials // on the fly. We are not doing this often so should be ok. @@ -296,6 +306,11 @@ void Ogre2LaserRetroMaterialSwitcher::postRenderTargetUpdate( Ogre::SubItem *subItem = it.first; subItem->setDatablock(it.second); } + + Ogre::Pass *pass = + this->laserRetroSourceMaterial->getBestTechnique()->getPass(0u); + pass->getVertexProgramParameters()->setNamedConstant( + "ignMinClipDistance", 0.0f ); } diff --git a/ogre2/src/media/materials/programs/plain_color_vs.glsl b/ogre2/src/media/materials/programs/plain_color_vs.glsl index 240d20d18..68a9047da 100644 --- a/ogre2/src/media/materials/programs/plain_color_vs.glsl +++ b/ogre2/src/media/materials/programs/plain_color_vs.glsl @@ -19,14 +19,30 @@ in vec4 vertex; uniform mat4 worldViewProj; +uniform mat4 worldView; +uniform float ignMinClipDistance; out gl_PerVertex { vec4 gl_Position; + float gl_ClipDistance[1]; }; void main() { // Calculate output position gl_Position = worldViewProj * vertex; + + if( ignMinClipDistance > 0.0f ) + { + // Frustum is rectangular; but the minimum lidar distance is spherical, + // so we can't rely on near plane to clip geometry that is too close, + // we have to do it by hand + vec3 viewSpacePos = (worldView * vertex).xyz; + gl_ClipDistance[0] = length( viewSpacePos.xyz ) - ignMinClipDistance; + } + else + { + gl_ClipDistance[0] = 1.0f; + } } diff --git a/ogre2/src/media/materials/scripts/gpu_rays.material b/ogre2/src/media/materials/scripts/gpu_rays.material index fb027f569..d1f49e863 100644 --- a/ogre2/src/media/materials/scripts/gpu_rays.material +++ b/ogre2/src/media/materials/scripts/gpu_rays.material @@ -129,10 +129,13 @@ material GpuRaysScan2nd vertex_program laser_retro_vs glsl { source plain_color_vs.glsl + num_clip_distances 1 default_params { param_named_auto worldViewProj worldviewproj_matrix + param_named_auto worldView worldview_matrix + param_named ignMinClipDistance float 0.0 } } diff --git a/ogre2/src/media/materials/scripts/picker.material b/ogre2/src/media/materials/scripts/picker.material index 5bf67970e..2fec2bde3 100644 --- a/ogre2/src/media/materials/scripts/picker.material +++ b/ogre2/src/media/materials/scripts/picker.material @@ -1,10 +1,13 @@ vertex_program plaincolor_vs glsl { source plain_color_vs.glsl + num_clip_distances 1 default_params { param_named_auto worldViewProj worldviewproj_matrix + param_named_auto worldView worldview_matrix + param_named ignMinClipDistance float 0.0 } } diff --git a/ogre2/src/media/materials/scripts/thermal.material b/ogre2/src/media/materials/scripts/thermal.material index eecc3f19a..840c07e70 100644 --- a/ogre2/src/media/materials/scripts/thermal.material +++ b/ogre2/src/media/materials/scripts/thermal.material @@ -60,10 +60,13 @@ material ThermalCamera vertex_program heat_source_vs glsl { source plain_color_vs.glsl + num_clip_distances 1 default_params { param_named_auto worldViewProj worldviewproj_matrix + param_named_auto worldView worldview_matrix + param_named ignMinClipDistance float 0.0 } }