Skip to content

Commit

Permalink
Use clipping distance for minimum LIDAR distance (#365)
Browse files Browse the repository at this point in the history
* 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 <[email protected]>

* 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 <[email protected]>
  • Loading branch information
darksylinc authored and iche033 committed Sep 9, 2021
1 parent 4153898 commit 6643f2f
Show file tree
Hide file tree
Showing 12 changed files with 339 additions and 2 deletions.
4 changes: 4 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ namespace ignition
//
// forward declaration
class Ogre2RenderEnginePrivate;
class Ogre2IgnHlmsCustomizations;

/// \brief Plugin for loading ogre render engine
class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2RenderEnginePlugin :
Expand Down Expand Up @@ -170,6 +171,9 @@ namespace ignition
/// \return a list of FSAA levels
public: std::vector<unsigned int> 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.
Expand Down
23 changes: 23 additions & 0 deletions ogre2/src/Ogre2GpuRays.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -212,6 +213,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.
Expand Down Expand Up @@ -308,6 +319,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 );
}


Expand Down Expand Up @@ -1237,8 +1253,15 @@ void Ogre2GpuRays::Render()
{
this->scene->StartRendering();

auto engine = Ogre2RenderEngine::Instance();
Ogre2IgnHlmsCustomizations &hlmsCustomizations =
engine->HlmsCustomizations();

hlmsCustomizations.minDistanceClip =
static_cast<float>(this->NearClipPlane());
this->UpdateRenderTarget1stPass();
this->UpdateRenderTarget2ndPass();
hlmsCustomizations.minDistanceClip = -1;

this->scene->FlushGpuCommandsAndStartNewFrame(6u, false);
}
Expand Down
121 changes: 121 additions & 0 deletions ogre2/src/Ogre2IgnHlmsCustomizations.cc
Original file line number Diff line number Diff line change
@@ -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 <OgreCamera.h>
#include <OgreHlms.h>
#include <OgreRenderTarget.h>
#include <OgreSceneManager.h>
#include <OgreViewport.h>
#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<float>(invViewProj[0][i]);
}
}
return _passBufferPtr;
}
118 changes: 118 additions & 0 deletions ogre2/src/Ogre2IgnHlmsCustomizations.hh
Original file line number Diff line number Diff line change
@@ -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 <OgreHlmsListener.h>
#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
20 changes: 20 additions & 0 deletions ogre2/src/Ogre2RenderEngine.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include "ignition/rendering/ogre2/Ogre2Scene.hh"
#include "ignition/rendering/ogre2/Ogre2Storage.hh"

#include "Ogre2IgnHlmsCustomizations.hh"

class ignition::rendering::Ogre2RenderEnginePrivate
{
Expand All @@ -50,6 +51,9 @@ class ignition::rendering::Ogre2RenderEnginePrivate

/// \brief A list of supported fsaa levels
public: std::vector<unsigned int> fsaaLevels;

/// \brief Controls Hlms customizations for both PBS and Unlit
public: ignition::rendering::Ogre2IgnHlmsCustomizations hlmsCustomizations;
};

using namespace ignition;
Expand Down Expand Up @@ -659,6 +663,10 @@ void Ogre2RenderEngine::RegisterHlms()

Ogre::ArchiveManager &archiveManager = Ogre::ArchiveManager::getSingleton();

Ogre::Archive *customizationsArchiveLibrary =
archiveManager.load( rootHlmsFolder + "Hlms/Ignition", "FileSystem",
true );

{
Ogre::HlmsUnlit *hlmsUnlit = 0;
// Create & Register HlmsUnlit
Expand All @@ -678,13 +686,16 @@ void Ogre2RenderEngine::RegisterHlms()
++libraryFolderPathIt;
}

archiveUnlitLibraryFolders.push_back( customizationsArchiveLibrary );

// Create and register the unlit Hlms
hlmsUnlit = OGRE_NEW Ogre::HlmsUnlit(archiveUnlit,
&archiveUnlitLibraryFolders);
Ogre::Root::getSingleton().getHlmsManager()->registerHlms(hlmsUnlit);

// disable writting debug output to disk
hlmsUnlit->setDebugOutputPath(false, false);
hlmsUnlit->setListener(&this->dataPtr->hlmsCustomizations);
}

{
Expand All @@ -708,12 +719,15 @@ void Ogre2RenderEngine::RegisterHlms()
++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);
}
}

Expand Down Expand Up @@ -873,6 +887,12 @@ std::vector<unsigned int> Ogre2RenderEngine::FSAALevels() const
return this->dataPtr->fsaaLevels;
}

/////////////////////////////////////////////////
Ogre2IgnHlmsCustomizations& Ogre2RenderEngine::HlmsCustomizations()
{
return this->dataPtr->hlmsCustomizations;
}

/////////////////////////////////////////////////
Ogre::v1::OverlaySystem *Ogre2RenderEngine::OverlaySystem() const
{
Expand Down
11 changes: 11 additions & 0 deletions ogre2/src/media/Hlms/Ignition/IgnCustomStructs_piece_all.any
Original file line number Diff line number Diff line change
@@ -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
Loading

0 comments on commit 6643f2f

Please sign in to comment.