Skip to content

Commit

Permalink
Merge 1a72c69 into ff16689
Browse files Browse the repository at this point in the history
  • Loading branch information
methylDragon authored May 23, 2022
2 parents ff16689 + 1a72c69 commit d0b250c
Show file tree
Hide file tree
Showing 16 changed files with 119 additions and 119 deletions.
4 changes: 2 additions & 2 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@ release will remove the deprecated code.
### Deprecations

1. **ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh**
+ Deprecated: `Ogre2IgnHlmsSphericalClipMinDistance &HlmsCustomizations()`
+ Replacement: `Ogre2IgnHlmsSphericalClipMinDistance &SphericalClipMinDistance()`
+ Deprecated: `Ogre2GzHlmsSphericalClipMinDistance &HlmsCustomizations()`
+ Replacement: `Ogre2GzHlmsSphericalClipMinDistance &SphericalClipMinDistance()`

## Ignition Rendering 6.2.1 to 6.X

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace ignition
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE
{
/// \brief Rendering modes so that IgnHlms implementations
/// \brief Rendering modes so that GzHlms implementations
/// follow alternate code paths or extra customizations
/// when they're enabled
enum IgnOgreRenderingMode
Expand Down
8 changes: 4 additions & 4 deletions ogre2/include/gz/rendering/ogre2/Ogre2RenderEngine.hh
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ namespace ignition
//
// forward declaration
class Ogre2RenderEnginePrivate;
class Ogre2IgnHlmsSphericalClipMinDistance;
class Ogre2GzHlmsSphericalClipMinDistance;

/// \brief Plugin for loading ogre render engine
class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2RenderEnginePlugin :
Expand Down Expand Up @@ -180,12 +180,12 @@ namespace ignition
public: std::vector<unsigned int> FSAALevels() const;

/// \brief Deprecated. Use SphericalClipMinDistance instead
public: Ogre2IgnHlmsSphericalClipMinDistance IGN_DEPRECATED(7) &
public: Ogre2GzHlmsSphericalClipMinDistance IGN_DEPRECATED(7) &
HlmsCustomizations();

/// \brief Retrieves Hlms customizations for tweaking them
/// \return Ogre HLMS customizations
public: Ogre2IgnHlmsSphericalClipMinDistance &SphericalClipMinDistance();
public: Ogre2GzHlmsSphericalClipMinDistance &SphericalClipMinDistance();

/// \internal
/// \brief Get a pointer to the Ogre overlay system.
Expand All @@ -194,7 +194,7 @@ namespace ignition

/// \internal
/// \brief Sets the current rendering mode. See IgnOgreRenderingMode
/// and see Ogre::IgnHlmsPbs
/// and see Ogre::GzHlmsPbs
/// \param[in] renderingMode
public: void SetIgnOgreRenderingMode(IgnOgreRenderingMode renderingMode);

Expand Down
4 changes: 2 additions & 2 deletions ogre2/src/Ogre2GpuRays.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "ignition/rendering/ogre2/Ogre2Sensor.hh"
#include "ignition/rendering/ogre2/Ogre2Visual.hh"

#include "Ogre2IgnHlmsSphericalClipMinDistance.hh"
#include "Ogre2GzHlmsSphericalClipMinDistance.hh"
#include "Ogre2ParticleNoiseListener.hh"
#include "Terra/Hlms/PbsListener/OgreHlmsPbsTerraShadows.h"

Expand Down Expand Up @@ -1409,7 +1409,7 @@ void Ogre2GpuRays::Render()
// These customization can be used to implement multi-tiered
// "near plane distances" as proposed in:
// https://github.com/ignitionrobotics/ign-rendering/issues/395
Ogre2IgnHlmsSphericalClipMinDistance &hlmsCustomizations =
Ogre2GzHlmsSphericalClipMinDistance &hlmsCustomizations =
engine->SphericalClipMinDistance();

hlmsCustomizations.minDistanceClip =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
*
*/

#include "Ogre2IgnHlmsPbsPrivate.hh"
#include "Ogre2GzHlmsPbsPrivate.hh"

#include "Terra/Hlms/PbsListener/OgreHlmsPbsTerraShadows.h"

Expand Down Expand Up @@ -45,9 +45,9 @@ namespace Ogre
/// \internal
static const uint16 kPerObjectDataBufferSlot = 4u;

Ogre2IgnHlmsPbs::Ogre2IgnHlmsPbs(
Ogre2GzHlmsPbs::Ogre2GzHlmsPbs(
Archive *dataFolder, ArchiveVec *libraryFolders,
Ogre2IgnHlmsSphericalClipMinDistance *_sphericalClipMinDistance,
Ogre2GzHlmsSphericalClipMinDistance *_sphericalClipMinDistance,
Ogre::HlmsPbsTerraShadows *terraShadows) :
HlmsPbs(dataFolder, libraryFolders)
{
Expand All @@ -56,7 +56,7 @@ namespace Ogre
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsPbs::preparePassHash(const CompositorShadowNode *_shadowNode,
void Ogre2GzHlmsPbs::preparePassHash(const CompositorShadowNode *_shadowNode,
bool _casterPass, bool _dualParaboloid,
SceneManager *_sceneManager,
Hlms *_hlms)
Expand All @@ -80,7 +80,7 @@ namespace Ogre
}

/////////////////////////////////////////////////
uint32 Ogre2IgnHlmsPbs::getPassBufferSize(
uint32 Ogre2GzHlmsPbs::getPassBufferSize(
const Ogre::CompositorShadowNode *_shadowNode, bool _casterPass,
bool _dualParaboloid, Ogre::SceneManager *_sceneManager) const
{
Expand All @@ -96,7 +96,7 @@ namespace Ogre
}

/////////////////////////////////////////////////
float *Ogre2IgnHlmsPbs::preparePassBuffer(
float *Ogre2GzHlmsPbs::preparePassBuffer(
const Ogre::CompositorShadowNode *_shadowNode, bool _casterPass,
bool _dualParaboloid, Ogre::SceneManager *_sceneManager,
float *_passBufferPtr)
Expand All @@ -112,7 +112,7 @@ namespace Ogre
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsPbs::shaderCacheEntryCreated(
void Ogre2GzHlmsPbs::shaderCacheEntryCreated(
const String &_shaderProfile, const HlmsCache *_hlmsCacheEntry,
const HlmsCache &_passCache, const HlmsPropertyVec &_properties,
const QueuedRenderable &_queuedRenderable)
Expand All @@ -127,15 +127,15 @@ namespace Ogre
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsPbs::notifyPropertiesMergedPreGenerationStep()
void Ogre2GzHlmsPbs::notifyPropertiesMergedPreGenerationStep()
{
HlmsPbs::notifyPropertiesMergedPreGenerationStep();

setProperty("IgnPerObjectDataSlot", kPerObjectDataBufferSlot);
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsPbs::hlmsTypeChanged(bool _casterPass,
void Ogre2GzHlmsPbs::hlmsTypeChanged(bool _casterPass,
CommandBuffer *_commandBuffer,
const HlmsDatablock *_datablock)
{
Expand All @@ -156,7 +156,7 @@ namespace Ogre
}

/////////////////////////////////////////////////
uint32 Ogre2IgnHlmsPbs::fillBuffersForV1(
uint32 Ogre2GzHlmsPbs::fillBuffersForV1(
const HlmsCache *_cache, const QueuedRenderable &_queuedRenderable,
bool _casterPass, uint32 _lastCacheHash, CommandBuffer *_commandBuffer)
{
Expand Down Expand Up @@ -198,7 +198,7 @@ namespace Ogre
}

/////////////////////////////////////////////////
uint32 Ogre2IgnHlmsPbs::fillBuffersForV2(
uint32 Ogre2GzHlmsPbs::fillBuffersForV2(
const HlmsCache *_cache, const QueuedRenderable &_queuedRenderable,
bool _casterPass, uint32 _lastCacheHash, CommandBuffer *_commandBuffer)
{
Expand Down Expand Up @@ -257,14 +257,14 @@ namespace Ogre
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsPbs::preCommandBufferExecution(CommandBuffer *_commandBuffer)
void Ogre2GzHlmsPbs::preCommandBufferExecution(CommandBuffer *_commandBuffer)
{
this->UnmapObjectDataBuffer();
HlmsPbs::preCommandBufferExecution(_commandBuffer);
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsPbs::frameEnded()
void Ogre2GzHlmsPbs::frameEnded()
{
HlmsPbs::frameEnded();

Expand All @@ -274,7 +274,7 @@ namespace Ogre
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsPbs::GetDefaultPaths(String &_outDataFolderPath,
void Ogre2GzHlmsPbs::GetDefaultPaths(String &_outDataFolderPath,
StringVector &_outLibraryFoldersPaths)
{
HlmsPbs::getDefaultPaths(_outDataFolderPath, _outLibraryFoldersPaths);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@
* limitations under the License.
*
*/
#ifndef IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSPBSPRIVATE_HH_
#define IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSPBSPRIVATE_HH_
#ifndef IGNITION_RENDERING_OGRE2_OGRE2GZHLMSPBSPRIVATE_HH_
#define IGNITION_RENDERING_OGRE2_OGRE2GZHLMSPBSPRIVATE_HH_

#include "ignition/rendering/config.hh"
#include "ignition/rendering/ogre2/Export.hh"

#include "Ogre2IgnHlmsSphericalClipMinDistance.hh"
#include "Ogre2IgnHlmsSharedPrivate.hh"
#include "Ogre2GzHlmsSphericalClipMinDistance.hh"
#include "Ogre2GzHlmsSharedPrivate.hh"

#ifdef _MSC_VER
#pragma warning(push, 0)
Expand Down Expand Up @@ -58,21 +58,21 @@ namespace Ogre
/// \internal
/// \remark Public variables take effect immediately (i.e. for the
/// next render)
class IGNITION_RENDERING_OGRE2_HIDDEN Ogre2IgnHlmsPbs final
class IGNITION_RENDERING_OGRE2_HIDDEN Ogre2GzHlmsPbs final
: public HlmsPbs,
public HlmsListener,
public ignition::rendering::Ogre2IgnHlmsShared
public ignition::rendering::Ogre2GzHlmsShared
{
/// \brief Constructor. Asks for modular listeners so we can add
/// them in the proper order
public: Ogre2IgnHlmsPbs(Archive *dataFolder, ArchiveVec *libraryFolders,
public: Ogre2GzHlmsPbs(Archive *dataFolder, ArchiveVec *libraryFolders,
ignition::rendering::
Ogre2IgnHlmsSphericalClipMinDistance
Ogre2GzHlmsSphericalClipMinDistance
*_sphericalClipMinDistance,
Ogre::HlmsPbsTerraShadows *terraShadows);

/// \brief Destructor. Virtual to silence warnings
public: virtual ~Ogre2IgnHlmsPbs() override = default;
public: virtual ~Ogre2GzHlmsPbs() override = default;

// Documentation inherited
public: using HlmsPbs::preparePassHash;
Expand Down Expand Up @@ -136,7 +136,7 @@ namespace Ogre
/// \param[in] _casterPass true if this is a caster pass
/// \param[in] _commandBuffer command buffer so we can add commands
/// \param[in] _datablock material of the object that caused
/// Ogre2IgnHlmsPbs to be bound again
/// Ogre2GzHlmsPbs to be bound again
public: virtual void hlmsTypeChanged(
bool _casterPass,
CommandBuffer *_commandBuffer,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
*
*/

#include "Ogre2IgnHlmsSharedPrivate.hh"
#include "Ogre2GzHlmsSharedPrivate.hh"

#include <ignition/common/Util.hh>

Expand All @@ -38,7 +38,7 @@ namespace ignition
namespace rendering
{
/////////////////////////////////////////////////
void Ogre2IgnHlmsShared::BindObjectDataBuffer(
void Ogre2GzHlmsShared::BindObjectDataBuffer(
Ogre::CommandBuffer *_commandBuffer, uint16_t _perObjectDataBufferSlot)
{
if (this->currPerObjectDataBuffer)
Expand All @@ -53,7 +53,7 @@ namespace ignition
}

/////////////////////////////////////////////////
float *Ogre2IgnHlmsShared::MapObjectDataBufferFor(
float *Ogre2GzHlmsShared::MapObjectDataBufferFor(
uint32_t _instanceIdx, Ogre::CommandBuffer *_commandBuffer,
Ogre::VaoManager *_vaoManager, const ConstBufferPackedVec &_constBuffers,
uint32_t _currConstBufferIdx, uint32_t *_startMappedConstBuffer,
Expand Down Expand Up @@ -105,7 +105,7 @@ namespace ignition
}

/////////////////////////////////////////////////
void Ogre2IgnHlmsShared::UnmapObjectDataBuffer()
void Ogre2GzHlmsShared::UnmapObjectDataBuffer()
{
if (this->currPerObjectDataBuffer)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
* limitations under the License.
*
*/
#ifndef IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSSHAREDPRIVATE_HH_
#define IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSSHAREDPRIVATE_HH_
#ifndef IGNITION_RENDERING_OGRE2_OGRE2GZHLMSSHAREDPRIVATE_HH_
#define IGNITION_RENDERING_OGRE2_OGRE2GZHLMSSHAREDPRIVATE_HH_

#include "ignition/rendering/config.hh"
#include "ignition/rendering/ogre2/Export.hh"
Expand Down Expand Up @@ -44,7 +44,7 @@ namespace ignition
/// \brief Implements code shared across all or most of our Hlms
/// customizations
/// \internal
class IGNITION_RENDERING_OGRE2_HIDDEN Ogre2IgnHlmsShared
class IGNITION_RENDERING_OGRE2_HIDDEN Ogre2GzHlmsShared
{
/// \brief Binds currPerObjectDataBuffer to the right slot.
/// Does nothing if it's nullptr
Expand All @@ -71,7 +71,7 @@ namespace ignition
/// for validation (to ensure our implementation isn't out of sync
/// with Ogre's)
/// \param[in] _perObjectDataBufferSlot See
/// Ogre2IgnHlmsShared::BindObjectDataBuffer
/// Ogre2GzHlmsShared::BindObjectDataBuffer
/// \return Pointer to write data for that instance
/// \internal
protected: float *MapObjectDataBufferFor(uint32_t _instanceIdx,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
*
*/

#include "Ogre2IgnHlmsSphericalClipMinDistance.hh"
#include "Ogre2GzHlmsSphericalClipMinDistance.hh"

#include "ignition/rendering/ogre2/Ogre2RenderEngine.hh"

Expand All @@ -35,7 +35,7 @@ using namespace ignition;
using namespace rendering;

//////////////////////////////////////////////////
void Ogre2IgnHlmsSphericalClipMinDistance::preparePassHash(
void Ogre2GzHlmsSphericalClipMinDistance::preparePassHash(
const Ogre::CompositorShadowNode * /*_shadowNode*/, bool _casterPass,
bool /*_dualParaboloid*/, Ogre::SceneManager * /*_sceneManager*/,
Ogre::Hlms *_hlms)
Expand All @@ -61,7 +61,7 @@ void Ogre2IgnHlmsSphericalClipMinDistance::preparePassHash(
}

//////////////////////////////////////////////////
Ogre::uint32 Ogre2IgnHlmsSphericalClipMinDistance::getPassBufferSize(
Ogre::uint32 Ogre2GzHlmsSphericalClipMinDistance::getPassBufferSize(
const Ogre::CompositorShadowNode * /*_shadowNode*/, bool _casterPass,
bool /*_dualParaboloid*/, Ogre::SceneManager * /*_sceneManager*/) const
{
Expand All @@ -76,7 +76,7 @@ Ogre::uint32 Ogre2IgnHlmsSphericalClipMinDistance::getPassBufferSize(
}

//////////////////////////////////////////////////
float *Ogre2IgnHlmsSphericalClipMinDistance::preparePassBuffer(
float *Ogre2GzHlmsSphericalClipMinDistance::preparePassBuffer(
const Ogre::CompositorShadowNode * /*_shadowNode*/, bool _casterPass,
bool /*_dualParaboloid*/, Ogre::SceneManager *_sceneManager,
float *_passBufferPtr)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSCUSTOMIZATIONS_HH_
#define IGNITION_RENDERING_OGRE2_OGRE2IGNHLMSCUSTOMIZATIONS_HH_
#ifndef IGNITION_RENDERING_OGRE2_OGRE2GZHLMSCUSTOMIZATIONS_HH_
#define IGNITION_RENDERING_OGRE2_OGRE2GZHLMSCUSTOMIZATIONS_HH_

#include "ignition/rendering/config.hh"
#include "ignition/rendering/ogre2/Export.hh"
Expand Down Expand Up @@ -46,10 +46,10 @@ namespace ignition
/// \internal
/// \remark Public variables take effect immediately (i.e. for the
/// next render)
class IGNITION_RENDERING_OGRE2_HIDDEN Ogre2IgnHlmsSphericalClipMinDistance
class IGNITION_RENDERING_OGRE2_HIDDEN Ogre2GzHlmsSphericalClipMinDistance
final : public Ogre::HlmsListener
{
public: virtual ~Ogre2IgnHlmsSphericalClipMinDistance() = default;
public: virtual ~Ogre2GzHlmsSphericalClipMinDistance() = default;

/// \brief
/// \return Returns true if spherical clipping customizations should
Expand All @@ -72,7 +72,7 @@ namespace ignition
/// bigger to fit our data we need to send
///
/// This data is sent in
/// Ogre2IgnHlmsSphericalClipMinDistance::preparePassBuffer
/// Ogre2GzHlmsSphericalClipMinDistance::preparePassBuffer
/// \param _casterPass
/// \param _hlms
private: virtual Ogre::uint32 getPassBufferSize(
Expand All @@ -82,7 +82,7 @@ namespace ignition

/// \brief Sends our custom data to GPU buffers that our
/// pieces activated in
/// Ogre2IgnHlmsSphericalClipMinDistance::preparePassHash will need.
/// Ogre2GzHlmsSphericalClipMinDistance::preparePassHash will need.
///
/// Bytes written must not exceed what we informed in getPassBufferSize
/// \param _casterPass
Expand Down
Loading

0 comments on commit d0b250c

Please sign in to comment.