Skip to content

Commit

Permalink
Merge branch 'ign-rendering6' into merge_5_6_20211018
Browse files Browse the repository at this point in the history
  • Loading branch information
iche033 authored Oct 19, 2021
2 parents 036c5de + 7c1430d commit 5a5f4cd
Show file tree
Hide file tree
Showing 11 changed files with 374 additions and 3 deletions.
5 changes: 5 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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 :
Expand Down Expand Up @@ -173,6 +174,10 @@ namespace ignition
/// \return a list of FSAA levels
public: std::vector<unsigned int> 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.
Expand Down
56 changes: 53 additions & 3 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 @@ -186,6 +187,9 @@ class ignition::rendering::Ogre2GpuRaysPrivate
/// emitter region
public: std::unique_ptr<Ogre2ParticleNoiseListener> 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;
};
Expand All @@ -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.
Expand Down Expand Up @@ -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 );
}


Expand Down Expand Up @@ -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);
Expand All @@ -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());
}

Expand Down Expand Up @@ -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));
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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<float>(this->NearClipPlane());
this->UpdateRenderTarget1stPass();
this->UpdateRenderTarget2ndPass();
hlmsCustomizations.minDistanceClip = -1;

this->scene->FlushGpuCommandsAndStartNewFrame(6u, false);
}
Expand Down
128 changes: 128 additions & 0 deletions ogre2/src/Ogre2IgnHlmsCustomizations.cc
Original file line number Diff line number Diff line change
@@ -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 <OgreCamera.h>
#include <OgreHlms.h>
#include <OgreRoot.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())
{
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<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
Loading

0 comments on commit 5a5f4cd

Please sign in to comment.