Skip to content

Commit

Permalink
Add LensFlare to ogre1 (#775)
Browse files Browse the repository at this point in the history
Previous PR #752 added LensFlarePass to ogre2.
This PR adds LensFlarePass to ogre1.

This includes LensFlarePass support for ogre1's WideAngleCamera.
WideAngleCamera had to be modified a little to support RenderPass at all.

In theory the gaussian filter pass should also work with WideAngleCamera but I did not test it.

It also implements OgreWideAngleCamera::Copy so that integration tests can function (Ogre2WideAngleCamera::Copy had already been implemented).

OgreRayQuery also had to be modified to support OgreWideAngleCamera; since LensFlares need ray queries for occlusion support.

Additionally I add RemoveAllRenderPasses since I noticed a lot of RenderPasses didn't get to properly deinitialize. Though it didn't seem like much harm was being done because currently all RenderPasses are very simple.

Signed-off-by: Matias N. Goldberg <[email protected]>
  • Loading branch information
darksylinc authored Dec 19, 2022
1 parent 93090c5 commit 73a4ff4
Show file tree
Hide file tree
Showing 43 changed files with 1,748 additions and 146 deletions.
3 changes: 3 additions & 0 deletions include/gz/rendering/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -348,6 +348,9 @@ namespace gz
/// \param[in] _pass render pass to remove
public: virtual void RemoveRenderPass(const RenderPassPtr &_pass) = 0;

/// \brief Remove all render passes from the camera
public: virtual void RemoveAllRenderPasses() = 0;

/// \brief Get the number of render passes applied to the camera
/// \return Number of render passes applied
public: virtual unsigned int RenderPassCount() const = 0;
Expand Down
6 changes: 6 additions & 0 deletions include/gz/rendering/LensFlarePass.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,12 @@ namespace gz
class GZ_RENDERING_VISIBLE LensFlarePass
: public virtual RenderPass
{
/// \brief Constructor
public: LensFlarePass();

/// \brief Destructor
public: virtual ~LensFlarePass();

/// \brief Initializes the Lens Flare Pass with given scene
/// \param[in] _scene Pointer to scene
public: virtual void Init(ScenePtr _scene) = 0;
Expand Down
19 changes: 19 additions & 0 deletions include/gz/rendering/RenderPass.hh
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,25 @@ namespace gz
/// to the camera that is about to render
/// \param[in] _camera Camera that is about to render
public: virtual void PreRender(const CameraPtr &_camera) = 0;

/// \brief WideAngleCamera renders to 6 faces; then stitches all 6
/// into a final "fish-eye" lens result.
///
/// This function controls whether the effect is applied to each 6
/// faces individually; or during the "stitching" pass.
///
/// The default setting depends on the RenderPass (e.g. LensFlare
/// defaults to true)
/// \remark This setting must not be changed after adding the RenderPass
/// to a Camera.
/// \param[in] _afterStitching True if it should be done after stitching,
/// False if it should be done to each of the 6 faces separately.
public: virtual void SetWideAngleCameraAfterStitching(
bool _afterStitching) = 0;

/// \brief See SetWideAngleCameraAfterStitching()
/// \return The current value set by SetWideAngleCameraAfterStitching
public: virtual bool WideAngleCameraAfterStitching() const = 0;
};
}
}
Expand Down
3 changes: 3 additions & 0 deletions include/gz/rendering/RenderTarget.hh
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,9 @@ namespace gz
/// \param[in] _pass render pass to remove
public: virtual void RemoveRenderPass(const RenderPassPtr &_pass) = 0;

/// \brief Remove all render passes from the render target
public: virtual void RemoveAllRenderPasses() = 0;

/// \brief Get the number of render passes applied to the render target
/// \return Number of render passes applied
public: virtual unsigned int RenderPassCount() const = 0;
Expand Down
14 changes: 14 additions & 0 deletions include/gz/rendering/base/BaseCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,9 @@ namespace gz
public: virtual void RemoveRenderPass(const RenderPassPtr &_pass)
override;

// Documentation inherited.
public: void RemoveAllRenderPasses() override;

// Documentation inherited.
public: virtual unsigned int RenderPassCount() const override;

Expand Down Expand Up @@ -860,6 +863,17 @@ namespace gz
this->RenderTarget()->RemoveRenderPass(_pass);
}

//////////////////////////////////////////////////
template <class T>
void BaseCamera<T>::RemoveAllRenderPasses()
{
RenderTargetPtr renderTarget = this->RenderTarget();
if (renderTarget)
{
renderTarget->RemoveAllRenderPasses();
}
}

//////////////////////////////////////////////////
template <class T>
unsigned int BaseCamera<T>::RenderPassCount() const
Expand Down
26 changes: 26 additions & 0 deletions include/gz/rendering/base/BaseRenderPass.hh
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,19 @@ namespace gz
// Documentation inherited
public: void PreRender(const CameraPtr &_camera) override;

// Documentation inherited
public: void SetWideAngleCameraAfterStitching(bool _afterStitching)
override;

// Documentation inherited
public: bool WideAngleCameraAfterStitching() const override;

/// \brief Flag to indicate if render pass is enabled or not
protected: bool enabled = true;

/// \brief Flag tracking the current value of
/// SetWideAngleCameraAfterStitching()
protected: bool afterStitching = false;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -89,6 +100,21 @@ namespace gz
T *thisT = this;
thisT->PreRender(); // NOT the same as doing T::PreRender
}

//////////////////////////////////////////////////
template <class T>
void BaseRenderPass<T>::SetWideAngleCameraAfterStitching(
bool _afterStitching)
{
this->afterStitching = _afterStitching;
}

//////////////////////////////////////////////////
template <class T>
bool BaseRenderPass<T>::WideAngleCameraAfterStitching() const
{
return this->afterStitching;
}
}
}
}
Expand Down
18 changes: 18 additions & 0 deletions include/gz/rendering/base/BaseRenderTarget.hh
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,9 @@ namespace gz
public: virtual void RemoveRenderPass(const RenderPassPtr &_pass)
override;

// Documentation inherited
public: void RemoveAllRenderPasses() override;

// Documentation inherited
public: virtual unsigned int RenderPassCount() const override;

Expand Down Expand Up @@ -278,6 +281,21 @@ namespace gz
}
}

//////////////////////////////////////////////////
template <class T>
void BaseRenderTarget<T>::RemoveAllRenderPasses()
{
if (!this->renderPasses.empty())
{
for (RenderPassPtr &renderPass : this->renderPasses)
{
renderPass->Destroy();
}
this->renderPasses.clear();
this->renderPassDirty = true;
}
}

//////////////////////////////////////////////////
template <class T>
unsigned int BaseRenderTarget<T>::RenderPassCount() const
Expand Down
3 changes: 2 additions & 1 deletion ogre/include/gz/rendering/ogre/OgreGaussianNoisePass.hh
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,8 @@ namespace gz
public: void CreateRenderPass() override;

/// \brief Gaussian noise compositor.
public: Ogre::CompositorInstance *gaussianNoiseInstance = nullptr;
public: Ogre::CompositorInstance *gaussianNoiseInstance
[kMaxOgreRenderPassCameras] = {};

/// \brief Gaussian noise compositor listener
GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
Expand Down
99 changes: 99 additions & 0 deletions ogre/include/gz/rendering/ogre/OgreLensFlarePass.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
/*
* Copyright (C) 2022 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 GZ_RENDERING_OGRE_OGRELENSFLAREPASS_HH_
#define GZ_RENDERING_OGRE_OGRELENSFLAREPASS_HH_

#include <memory>

#include <gz/utils/ImplPtr.hh>

#include "gz/math/Vector3.hh"

#include "gz/rendering/base/BaseLensFlarePass.hh"
#include "gz/rendering/ogre/Export.hh"
#include "gz/rendering/ogre/OgreRenderPass.hh"

namespace gz
{
namespace rendering
{
inline namespace GZ_RENDERING_VERSION_NAMESPACE {

/// \brief Ogre Implementation of a Lens Flare render pass.
class GZ_RENDERING_OGRE_VISIBLE OgreLensFlarePass :
public BaseLensFlarePass<OgreRenderPass>
{
/// \brief Constructor
public: OgreLensFlarePass();

/// \brief Destructor
public: ~OgreLensFlarePass() override;

// Documentation inherited
public: void Init(ScenePtr _scene) override;

// Documentation inherited
public: void Destroy() override;

// Documentation inherited
public: void CreateRenderPass() override;

// Documentation inherited
public: void PreRender(const CameraPtr &_camera) override;

// Documentation inherited
public: void PostRender() override;

// Documentation inherited
public: void SetScale(double _scale) override;

// Documentation inherited
public: double Scale() const override;

// Documentation inherited
public: void SetColor(const math::Vector3d &_color) override;

// Documentation inherited
public: const math::Vector3d &Color() const override;

// Documentation inherited
public: void SetOcclusionSteps(uint32_t _occlusionSteps) override;

// Documentation inherited
public: uint32_t OcclusionSteps() const override;

/// \brief Check to see if the lens flare is occluded and return a scaling
/// factor that is proportional to the lens flare's visibility
/// \remark OgreLensFlarePass::PreRender must have been called first.
/// \param[in] _imgPos light pos in clip space
/// \param[in] _faceIdx Face idx in range [0; 6)
/// See RayQuery::SetFromCamera for what each value means
/// This value is ignored if the camera is not WideAngleCamera
private: double OcclusionScale(const math::Vector3d &_imgPos,
uint32_t _faceIdx);

/// \cond warning
/// \brief Private data pointer
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
/// \endcond

private: friend class OgreLensFlareCompositorListenerPrivate;
};
}
}
}
#endif
13 changes: 12 additions & 1 deletion ogre/include/gz/rendering/ogre/OgreRenderPass.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@ namespace gz
namespace rendering
{
inline namespace GZ_RENDERING_VERSION_NAMESPACE {

static constexpr uint32_t kMaxOgreRenderPassCameras = 6u;

//
/* \class OgreRenderPass OgreRenderPass.hh \
* gz/rendering/ogre/OgreRenderPass.hh
Expand All @@ -45,14 +48,22 @@ namespace gz
/// \param[in] _camera Pointer to the ogre camera.
public: virtual void SetCamera(Ogre::Camera *_camera);

/// \brief Set all ogre cameras that the render pass applies to
/// at once.
/// \param[in] _cameras Pointer to the ogre cameras.
public: virtual void SetCameras(
Ogre::Camera *_cameras[kMaxOgreRenderPassCameras]);

// Documentation inherited.
public: void Destroy() override;

/// \brief Create the render pass using ogre compositor
public: virtual void CreateRenderPass();

/// \brief Pointer to the ogre camera
protected: Ogre::Camera *ogreCamera = nullptr;
/// May have more than one. Must check for nullptr on all of them.
/// Not all RenderPasses support multiple cameras
protected: Ogre::Camera *ogreCamera[kMaxOgreRenderPassCameras] = {};
};
}
}
Expand Down
19 changes: 19 additions & 0 deletions ogre/include/gz/rendering/ogre/OgreWideAngleCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -59,12 +59,28 @@ namespace gz
/// \brief Create a texture
public: virtual void CreateRenderTexture();

/// \brief Destroy render texture created by CreateRenderTexture()
/// Note: It's not virtual.
protected: void DestroyRenderTexture();

/// \brief Render the camera
public: virtual void PostRender() override;

// Documentation inherited
public: virtual void Destroy() override;

// Documentation inherited
public: void AddRenderPass(const RenderPassPtr &_pass) override;

// Documentation inherited
public: void RemoveRenderPass(const RenderPassPtr &_pass) override;

// Documentation inherited
public: void RemoveAllRenderPasses() override;

/// \brief Update render pass chain if changes were made
protected: void UpdateRenderPassChain();

/// \brief Gets the environment texture size
/// \return Texture size
public: unsigned int EnvTextureSize() const;
Expand Down Expand Up @@ -105,6 +121,9 @@ namespace gz
/// \brief Implementation of the render call
public: virtual void Render() override;

// Documentation inherited.
public: void Copy(Image &_image) const override;

// Documentation inherited
public: common::ConnectionPtr ConnectNewWideAngleFrame(
std::function<void(const unsigned char *, unsigned int, unsigned int,
Expand Down
1 change: 1 addition & 0 deletions ogre/src/OgreCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ void OgreCamera::Destroy()
if (!this->ogreCamera)
return;

this->RemoveAllRenderPasses();
this->DestroyRenderTexture();

Ogre::SceneManager *ogreSceneManager;
Expand Down
2 changes: 2 additions & 0 deletions ogre/src/OgreDepthCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,8 @@ OgreDepthCamera::~OgreDepthCamera()
//////////////////////////////////////////////////
void OgreDepthCamera::Destroy()
{
this->RemoveAllRenderPasses();

if (this->dataPtr->depthBuffer)
{
delete [] this->dataPtr->depthBuffer;
Expand Down
Loading

0 comments on commit 73a4ff4

Please sign in to comment.