From 7c1430daf5100314c9791bf9dc5c9386c4096b0b Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 18 Oct 2021 22:13:00 -0700 Subject: [PATCH] Merge pull request #356 from ignitionrobotics/lidar_near_clip Fix lidar near plane clipping --- .../rendering/ogre2/Ogre2RenderEngine.hh | 5 + ogre2/src/Ogre2GpuRays.cc | 56 +++++++- ogre2/src/Ogre2IgnHlmsCustomizations.cc | 128 ++++++++++++++++++ ogre2/src/Ogre2IgnHlmsCustomizations.hh | 118 ++++++++++++++++ ogre2/src/Ogre2RenderEngine.cc | 19 +++ .../Ignition/IgnCustomStructs_piece_all.any | 11 ++ .../src/media/Hlms/Ignition/Ign_piece_vs.any | 15 ++ .../materials/programs/plain_color_vs.glsl | 16 +++ .../media/materials/scripts/gpu_rays.material | 3 + .../media/materials/scripts/picker.material | 3 + .../media/materials/scripts/thermal.material | 3 + 11 files changed, 374 insertions(+), 3 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 42d1f53ab..ffe3a2194 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh @@ -52,6 +52,7 @@ namespace ignition // // forward declaration class Ogre2RenderEnginePrivate; + class Ogre2IgnHlmsCustomizations; /// \brief Plugin for loading ogre render engine class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2RenderEnginePlugin : @@ -173,6 +174,10 @@ namespace ignition /// \return a list of FSAA levels public: std::vector FSAALevels() const; + /// \brief Retrieves Hlms customizations for tweaking them + /// \return Ogre HLMS customizations + 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 ea2d28103..26b0f2064 100644 --- a/ogre2/src/Ogre2GpuRays.cc +++ b/ogre2/src/Ogre2GpuRays.cc @@ -33,6 +33,7 @@ #include "ignition/rendering/ogre2/Ogre2Sensor.hh" #include "ignition/rendering/ogre2/Ogre2Visual.hh" +#include "Ogre2IgnHlmsCustomizations.hh" #include "Ogre2ParticleNoiseListener.hh" #ifdef _MSC_VER @@ -186,6 +187,9 @@ class ignition::rendering::Ogre2GpuRaysPrivate /// emitter region public: std::unique_ptr particleNoiseListener[6]; + /// \brief Near clip plane for cube camera + public: float nearClipCube = 0.0; + /// \brief Min allowed angle in radians; public: const math::Angle kMinAllowedAngle = 1e-4; }; @@ -212,6 +216,16 @@ Ogre2LaserRetroMaterialSwitcher::Ogre2LaserRetroMaterialSwitcher( void Ogre2LaserRetroMaterialSwitcher::cameraPreRenderScene( Ogre::Camera * /*_cam*/) { + { + 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. @@ -309,6 +323,11 @@ void Ogre2LaserRetroMaterialSwitcher::cameraPostRenderScene( Ogre::SubItem *subItem = it.first; subItem->setDatablock(it.second); } + + Ogre::Pass *pass = + this->laserRetroSourceMaterial->getBestTechnique()->getPass(0u); + pass->getVertexProgramParameters()->setNamedConstant( + "ignMinClipDistance", 0.0f ); } @@ -515,8 +534,17 @@ void Ogre2GpuRays::ConfigureCamera() v |= v >> 8; v |= v >> 16; v++; + + // limit min texture size to 128 + // This is needed for large fov with low sample count, + // e.g. 360 degrees and only 4 samples. Otherwise the depth data returned are + // inaccurate. + // \todo(anyone) For small fov, we shouldn't need such a high min texture size + // requirement, e.g. a single ray lidar only needs 1x1 texture. Look for ways + // to compute the optimal min texture size + unsigned int min1stPassSamples = 128u; + // limit max texture size to 1024 - unsigned int min1stPassSamples = 2u; unsigned int max1stPassSamples = 1024u; unsigned int samples1stPass = std::clamp(v, min1stPassSamples, max1stPassSamples); @@ -527,7 +555,7 @@ void Ogre2GpuRays::ConfigureCamera() this->SetRangeCount(this->RangeCount(), this->VerticalRangeCount()); // Set ogre cam properties - this->dataPtr->ogreCamera->setNearClipDistance(this->NearClipPlane()); + this->dataPtr->ogreCamera->setNearClipDistance(this->dataPtr->nearClipCube); this->dataPtr->ogreCamera->setFarClipDistance(this->FarClipPlane()); } @@ -989,7 +1017,7 @@ void Ogre2GpuRays::Setup1stPass() this->ogreNode->attachObject(this->dataPtr->cubeCam[i]); this->dataPtr->cubeCam[i]->setFOVy(Ogre::Degree(90)); this->dataPtr->cubeCam[i]->setAspectRatio(1); - this->dataPtr->cubeCam[i]->setNearClipDistance(this->NearClipPlane()); + this->dataPtr->cubeCam[i]->setNearClipDistance(this->dataPtr->nearClipCube); this->dataPtr->cubeCam[i]->setFarClipDistance(this->FarClipPlane()); this->dataPtr->cubeCam[i]->setFixedYawAxis(false); this->dataPtr->cubeCam[i]->yaw(Ogre::Degree(-90)); @@ -1198,6 +1226,15 @@ void Ogre2GpuRays::Setup2ndPass() ///////////////////////////////////////////////////////// void Ogre2GpuRays::CreateGpuRaysTextures() { + // make cube cam near clip smaller than specified and manually clip range + // values in 1st pass shader (gpu_rays_1st_pass_fs.glsl). + // This is so that we don't incorrectly clip the range values near the + // corners of the cube cam viewport. + + // compute smallest box to fit in sphere with radius = this->NearClipPlane + double boxSize = this->NearClipPlane() * 2 / std::sqrt(3.0); + this->dataPtr->nearClipCube = boxSize * 0.5; + this->ConfigureCamera(); this->CreateSampleTexture(); this->Setup1stPass(); @@ -1247,8 +1284,21 @@ void Ogre2GpuRays::Render() { this->scene->StartRendering(nullptr); + auto engine = Ogre2RenderEngine::Instance(); + + // The Hlms customizations add a "spherical" clipping; which ignores depth + // clamping as it clips before sending vertices to the pixel shader. + // These customization can be used to implement multi-tiered + // "near plane distances" as proposed in: + // https://github.com/ignitionrobotics/ign-rendering/issues/395 + Ogre2IgnHlmsCustomizations &hlmsCustomizations = + engine->HlmsCustomizations(); + + hlmsCustomizations.minDistanceClip = + static_cast(this->NearClipPlane()); this->UpdateRenderTarget1stPass(); this->UpdateRenderTarget2ndPass(); + hlmsCustomizations.minDistanceClip = -1; this->scene->FlushGpuCommandsAndStartNewFrame(6u, false); } diff --git a/ogre2/src/Ogre2IgnHlmsCustomizations.cc b/ogre2/src/Ogre2IgnHlmsCustomizations.cc new file mode 100644 index 000000000..1cdeb5b0a --- /dev/null +++ b/ogre2/src/Ogre2IgnHlmsCustomizations.cc @@ -0,0 +1,128 @@ +/* + * 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" + +#include "ignition/rendering/ogre2/Ogre2RenderEngine.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()) + { + const Ogre::Camera *camera = + _sceneManager->getCamerasInProgress().renderingCamera; + 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) + auto engine = Ogre2RenderEngine::Instance(); + auto ogreRoot = engine->OgreRoot(); + Ogre::RenderPassDescriptor *renderPassDesc = + ogreRoot->getRenderSystem()->getCurrentPassDescriptor(); + Ogre::Matrix4 projectionMatrix = + camera->getProjectionMatrixWithRSDepth(); + if (renderPassDesc->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 cda537ea7..12ce79a5c 100644 --- a/ogre2/src/Ogre2RenderEngine.cc +++ b/ogre2/src/Ogre2RenderEngine.cc @@ -44,6 +44,7 @@ #include "Terra/Hlms/OgreHlmsTerra.h" #include "Terra/Hlms/PbsListener/OgreHlmsPbsTerraShadows.h" #include "Terra/TerraWorkspaceListener.h" +#include "Ogre2IgnHlmsCustomizations.hh" class ignition::rendering::Ogre2RenderEnginePrivate { @@ -54,6 +55,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; + /// \brief Pbs listener that adds terra shadows public: std::unique_ptr hlmsPbsTerraShadows; @@ -677,6 +681,10 @@ void Ogre2RenderEngine::RegisterHlms() Ogre::ArchiveManager &archiveManager = Ogre::ArchiveManager::getSingleton(); + Ogre::Archive *customizationsArchiveLibrary = + archiveManager.load(common::joinPaths(rootHlmsFolder, "Hlms", "Ignition"), + "FileSystem", true); + { Ogre::HlmsUnlit *hlmsUnlit = 0; // Create & Register HlmsUnlit @@ -696,6 +704,8 @@ void Ogre2RenderEngine::RegisterHlms() ++libraryFolderPathIt; } + archiveUnlitLibraryFolders.push_back(customizationsArchiveLibrary); + // Create and register the unlit Hlms hlmsUnlit = OGRE_NEW Ogre::HlmsUnlit(archiveUnlit, &archiveUnlitLibraryFolders); @@ -703,6 +713,7 @@ void Ogre2RenderEngine::RegisterHlms() // disable writting debug output to disk hlmsUnlit->setDebugOutputPath(false, false); + hlmsUnlit->setListener(&this->dataPtr->hlmsCustomizations); } { @@ -726,6 +737,7 @@ void Ogre2RenderEngine::RegisterHlms() ++libraryFolderPathIt; } + archivePbsLibraryFolders.push_back(customizationsArchiveLibrary); { archivePbsLibraryFolders.push_back(archiveManager.load( rootHlmsFolder + common::joinPaths("Hlms", "Terra", "GLSL", @@ -740,6 +752,7 @@ void Ogre2RenderEngine::RegisterHlms() // disable writting debug output to disk hlmsPbs->setDebugOutputPath(false, false); + hlmsPbs->setListener(&this->dataPtr->hlmsCustomizations); } { @@ -942,6 +955,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/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 6c1549360..2341df7e4 100644 --- a/ogre2/src/media/materials/scripts/gpu_rays.material +++ b/ogre2/src/media/materials/scripts/gpu_rays.material @@ -128,10 +128,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 } }