Skip to content

Commit

Permalink
Merge branch 'main' into lobotuerk/depthRangeChange
Browse files Browse the repository at this point in the history
  • Loading branch information
Lobotuerk authored Aug 2, 2021
2 parents 7981084 + 16014e7 commit b68668f
Show file tree
Hide file tree
Showing 19 changed files with 694 additions and 102 deletions.
83 changes: 83 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,89 @@

### Ignition Rendering 5.X.X (20XX-XX-XX)

### Ignition Rendering 5.1.0 (2021-06-22)

1. add ifdef for apple in integration test
* [Pull request #349](https://github.com/ignitionrobotics/ign-rendering/pull/349)

1. Update light map tutorial
* [Pull request #346](https://github.com/ignitionrobotics/ign-rendering/pull/346)

1. relax gaussian test tolerance
* [Pull request #344](https://github.com/ignitionrobotics/ign-rendering/pull/344)

1. Fix custom shaders uniforms ign version number
* [Pull request #343](https://github.com/ignitionrobotics/ign-rendering/pull/343)

1. recreate node only when needed
* [Pull request #342](https://github.com/ignitionrobotics/ign-rendering/pull/342)

1. Backport memory fixes found by ASAN
* [Pull request #340](https://github.com/ignitionrobotics/ign-rendering/pull/340)

1. Fix FSAA in UI and lower VRAM consumption
* [Pull request #313](https://github.com/ignitionrobotics/ign-rendering/pull/313)

1. Fix depth alpha
* [Pull request #316](https://github.com/ignitionrobotics/ign-rendering/pull/316)

1. Fix floating point precision bug handling alpha channel (#332)
* [Pull request #333](https://github.com/ignitionrobotics/ign-rendering/pull/333)

1. Fix heap overflow when reading
* [Pull request #337](https://github.com/ignitionrobotics/ign-rendering/pull/337)

1. Fix new [] / delete mismatch
* [Pull request #338](https://github.com/ignitionrobotics/ign-rendering/pull/338)

1. Test re-enabling depth camera integration test on mac
* [Pull request #335](https://github.com/ignitionrobotics/ign-rendering/pull/335)

1. Include MoveTo Helper class to ign-rendering
* [Pull request #311](https://github.com/ignitionrobotics/ign-rendering/pull/311)

1. Remove `tools/code_check` and update codecov
* [Pull request #321](https://github.com/ignitionrobotics/ign-rendering/pull/321)

1. [OGRE 1.x] Uniform buffer shader support
* [Pull request #294](https://github.com/ignitionrobotics/ign-rendering/pull/294)

1. Helper function to get a scene
* [Pull request #320](https://github.com/ignitionrobotics/ign-rendering/pull/320)

1. fix capsule mouse picking
* [Pull request #319](https://github.com/ignitionrobotics/ign-rendering/pull/319)

1. Fix depth alpha
* [Pull request #316](https://github.com/ignitionrobotics/ign-rendering/pull/316)

1. Add shadows to Ogre2DepthCamera without crashing
* [Pull request #303](https://github.com/ignitionrobotics/ign-rendering/pull/303)

1. Reduce lidar data discretization
* [Pull request #296](https://github.com/ignitionrobotics/ign-rendering/pull/296)

1. update light visual size
* [Pull request #306](https://github.com/ignitionrobotics/ign-rendering/pull/306)

1. Improve build times by reducing included headers
* [Pull request #299](https://github.com/ignitionrobotics/ign-rendering/pull/299)

1. Add light map tutorial
* [Pull request #302](https://github.com/ignitionrobotics/ign-rendering/pull/302)

1. Prevent console warnings when multiple texture coordinates are present
* [Pull request #301](https://github.com/ignitionrobotics/ign-rendering/pull/301)

1. Fix gazebo scene viewer build
* [Pull request #289](https://github.com/ignitionrobotics/ign-rendering/pull/289)

1. Silence noisy sky error
* [Pull request #282](https://github.com/ignitionrobotics/ign-rendering/pull/282)

1. Added command line argument to pick version of Ogre
* [Pull request #277](https://github.com/ignitionrobotics/ign-rendering/pull/277)

### Ignition Rendering 5.0.0 (2021-03-30)

1. Add ogre2 skybox support
Expand Down
31 changes: 31 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,37 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Ignition Rendering 5.x to 6.x

### Modifications

1. **Scene.hh**
+ Added `Scene::PostRender`. The function `Camera::Render` must be executed
between calls to `Scene::PreRender` and `Scene::PostRender`. Failure to do
so will result in asserts triggering informing users to correct their code.
Alternatively calling `Scene::SetCameraPassCountPerGpuFlush( 0 )` avoids
this strict requirement.
Users handling only one Camera can call `Camera::Update` or `Camera::Capture`
and thus do not need to worry.
However for more than one camera (of any type) the optimum way to handle them is to update them in the following pattern:
```
scene->PreRender();
for( auto& camera in cameras )
camera->Render();
for( auto& camera in cameras )
camera->PostRender();
scene->PostRender();
```
This pattern maximizes the chances of improving performance.
*Note*: Calling instead `Camera::Update` for each camera is a waste of CPU resources.
+ It is invalid to modify the scene between `Scene::PreRender` and `Scene::PostRender` (e.g. add/remove objects, lights, etc)
+ Added `Scene::SetCameraPassCountPerGpuFlush`. Setting this value to 0 forces legacy behavior which eases porting.
+ Systems that rely on Graphics components like particle FXs and postprocessing are explicitly affected by Scene's Pre/PostRender. Once `Scene::PostRender` is called, the particle FXs' simulation is moved forward, as well as time values sent to postprocessing shaders. In previous ign-rendering versions each `Camera::Render` call would move the particle simulation forward, which could cause subtle bugs or inconsistencies when Cameras were rendering the same frame from different angles. Setting SetCameraPassCountPerGpuFlush to 0 will also cause these subtle bugs to reappear.
1. **Visual.hh** and **Node.hh**
+ `*UserData` methods and the `Variant` type alias have been moved from the `Visual` class to the `Node` class.
`Node::UserData` now returns no data for keys that don't exist (prior to Rendering 6.x, if
`Visual::UserData` was called with a key that doesn't exist, an `int` was returned by default).
## Ignition Rendering 4.0 to 4.1
Expand Down
8 changes: 4 additions & 4 deletions include/ignition/rendering/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -152,8 +152,8 @@ namespace ignition
/// \brief Renders a new frame.
/// This is a convenience function for single-camera scenes. It wraps the
/// pre-render, render, and post-render into a single
/// function. This should be used in applications with multiple cameras
/// or multiple consumers of a single camera's images.
/// function. This should NOT be used in applications with multiple
/// cameras or multiple consumers of a single camera's images.
public: virtual void Update() = 0;

/// \brief Created an empty image buffer for capturing images. The
Expand All @@ -166,8 +166,8 @@ namespace ignition
/// \brief Renders a new frame and writes the results to the given image.
/// This is a convenience function for single-camera scenes. It wraps the
/// pre-render, render, post-render, and get-image calls into a single
/// function. This should be used in applications with multiple cameras
/// or multiple consumers of a single camera's images.
/// function. This should NOT be used in applications with multiple
/// cameras or multiple consumers of a single camera's images.
/// \param[out] _image Output image buffer
public: virtual void Capture(Image &_image) = 0;

Expand Down
34 changes: 30 additions & 4 deletions include/ignition/rendering/Node.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,10 @@
#ifndef IGNITION_RENDERING_NODE_HH_
#define IGNITION_RENDERING_NODE_HH_

#include <map>
#include <string>
#include <variant>

#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>

Expand All @@ -32,6 +35,17 @@ namespace ignition
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
//
/// \brief Alias for a variant that can hold various types of data.
/// The first type of the variant is std::monostate in order to prevent
/// default-constructed variants from holding a type (a default-constructed
/// variant is returned when a user calls Node::UserData with a key that
/// doesn't exist for the node. In this case, since the key doesn't
/// exist, the variant that is returned shouldn't hold any types - an
/// "empty variant" should be returned for keys that don't exist)
using Variant =
std::variant<std::monostate, int, float, double, std::string, bool,
unsigned int>;

/// \class Node Node.hh ignition/rendering/Node.hh
/// \brief Represents a single posable node in the scene graph
class IGNITION_RENDERING_VISIBLE Node :
Expand Down Expand Up @@ -222,12 +236,12 @@ namespace ignition
/// \param[in] _scale Scalars to alter the current scale
public: virtual void Scale(const math::Vector3d &_scale) = 0;

/// \brief Determine if this visual inherits scale from this parent
/// \return True if this visual inherits scale from this parent
/// \brief Determine if this node inherits scale from this parent
/// \return True if this node inherits scale from this parent
public: virtual bool InheritScale() const = 0;

/// \brief Specify if this visual inherits scale from its parent
/// \param[in] _inherit True if this visual inherits scale from its parent
/// \brief Specify if this node inherits scale from its parent
/// \param[in] _inherit True if this node inherits scale from its parent
public: virtual void SetInheritScale(bool _inherit) = 0;

/// \brief Get number of child nodes
Expand Down Expand Up @@ -302,6 +316,18 @@ namespace ignition
/// \brief Remove all child nodes from this node
/// This detaches all the child nodes but does not destroy them
public: virtual void RemoveChildren() = 0;

/// \brief Store any custom data associated with this node
/// \param[in] _key Unique key
/// \param[in] _value Value in any type
public: virtual void SetUserData(
const std::string &_key, Variant _value) = 0;

/// \brief Get custom data stored in this node
/// \param[in] _key Unique key
/// \return Value in any type. If _key does not exist for the node, an
/// empty variant is returned (i.e., no data).
public: virtual Variant UserData(const std::string &_key) const = 0;
};
}
}
Expand Down
114 changes: 114 additions & 0 deletions include/ignition/rendering/Scene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -1077,6 +1077,120 @@ namespace ignition
/// changes by traversing scene-graph, calling PreRender on all objects
public: virtual void PreRender() = 0;

/// \brief Call this function after you're done updating ALL cameras
/// \remark Each PreRender must have a correspondent PostRender
/// \remark Particle FX simulation is moved forward after this call
///
/// \see Scene::SetCameraPassCountPerGpuFlush
public: virtual void PostRender() = 0;

/// \brief
/// The ideal render loop is as follows:
///
/// \code
/// scene->PreRender();
/// for (auto &camera in cameras)
/// camera->Render();
/// for (auto &camera in cameras)
/// camera->PostRender();
/// scene->PostRender();
/// \endcode
///
/// Now... Camera Render calls MUST happen between Scene::PreRender and
/// Scene::PostRender.
///
/// The scene must not be modified (e.g. add/remove objects, lights, etc)
/// while inside Scene PreRender/PostRender
///
/// # Legacy mode: Set this value to 0.
///
/// Old projects migrating to newer ign versions may break
/// these rules (e.g. not calling Render between Scene's
/// Pre/PostRender).
///
/// Setting this value to 0 forces Gazebo to flush commands for
/// every camera; thus avoiding the need to call PostRender at all
///
/// This is much slower but will ease porting, specially
/// if it's not easy to adapt your code to call PostRender for some
/// reason (in non-legacy mode each call *must* correspond to a
/// previous PreRender call)
///
/// Legacy mode forces Particle FX simulations to move forward
/// after each camera render, which can cause inconsistencies
/// when Cameras are supposed to be rendering the same frame from
/// different angles
///
/// # New mode i.e. values greater than 0:
///
/// The CPU normally queues up of rendering commands from each Camera and
/// then waits for the GPU to finish up.
///
/// 1. If we flush too often, the CPU will often have to wait for
/// the GPU to finish.
/// 2. If we flush infrequently, RAM consumption will rise due to
/// queueing up too much unsubmitted work.
///
/// Larger values values queue up more work; lower values flush more
/// frequently.
///
/// Note that work may be submitted earlier if required by a specific
/// operation (e.g. reading GPU -> CPU)
///
/// A sensible value in the range of [2; 6] is probably the best
/// ratio between parallel performance / RAM cost.
///
/// Actual value depends on scene complexity and number of shadow
/// casting lights
///
/// If you're too tight on RAM consumption, try setting this value to 1.
///
/// ## Example:
///
/// Cubemap rendering w/ 3 probes and 5 shadowmaps can cause
/// a blow up of passes:
///
/// (5 shadow maps per face + 1 regular render) x 6 faces x 3 probes =
/// 108 render_scene passes.
/// 108 is way too much, causing out of memory situations;
///
/// so setting the value to 6 (1 cubemap face = 1 pass) will
/// force one flush per cubemap face, flushing a total of 3 times
/// (one per cubemap).
///
/// ## Upper bound
///
/// Once Scene::PostRender is called, a flush is always forced.
///
/// If you set a value of e.g. 6, but you have a single camera, it
/// will be flushed after Scene::PostRender, thus having a value of 1 or
/// 6 won't matter as the result will be exactly the same (in every term:
/// performance, memory consumption)
///
/// A value of 6 is like an upper bound.
/// We may queue _up to_ 6 render passes or less; but never more.
///
/// \remarks Not all rendering engines care about this.
/// ogre2 plugin does.
///
/// \param[in] _numPass 0 for old projects who can't or don't know
/// when to call PostRender and prefer to penalize rendering
/// performance
/// Value in range [1; 255]
public: virtual void SetCameraPassCountPerGpuFlush(uint8_t _numPass) = 0;

/// \brief Returns the value set in SetCameraPassCountPerGpuFlush
/// \return Value in range [0; 255].
/// ALWAYS returns 0 for plugins that ignore
/// SetCameraPassCountPerGpuFlush
public: virtual uint8_t CameraPassCountPerGpuFlush() const = 0;

/// \brief Checks if SetCameraPassCountPerGpuFlush is 0
/// \return True if Gazebo is using the old method (i.e. 0).
/// ALWAYS returns true for plugins that ignore
/// SetCameraPassCountPerGpuFlush
public: virtual bool LegacyAutoGpuFlush() const = 0;

/// \brief Remove and destroy all objects from the scene graph. This does
/// not completely destroy scene resources, so new objects can be created
/// and added to the scene afterwards.
Expand Down
15 changes: 0 additions & 15 deletions include/ignition/rendering/Visual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#ifndef IGNITION_RENDERING_VISUAL_HH_
#define IGNITION_RENDERING_VISUAL_HH_

#include <variant>
#include <string>
#include <ignition/math/AxisAlignedBox.hh>
#include "ignition/rendering/config.hh"
Expand All @@ -28,9 +27,6 @@ namespace ignition
namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
//
using Variant = std::variant<int, float, double, std::string>;

/// \class Visual Visual.hh ignition/rendering/Visual.hh
/// \brief Represents a visual node in a scene graph. A Visual is the only
/// node that can have Geometry and other Visual children.
Expand Down Expand Up @@ -138,17 +134,6 @@ namespace ignition
/// \param[in] _visibility flags
public: virtual void RemoveVisibilityFlags(uint32_t _flags) = 0;

/// \brief Store any custom data associated with this visual
/// \param[in] _key Unique key
/// \param[in] _value Value in any type
public: virtual void SetUserData(const std::string &_key,
Variant _value) = 0;

/// \brief Get custom data stored in this visual
/// \param[in] _key Unique key
/// \param[in] _value Value in any type
public: virtual Variant UserData(const std::string &_key) const = 0;

/// \brief Get the bounding box in world frame coordinates.
/// \return The axis aligned bounding box
public: virtual ignition::math::AxisAlignedBox BoundingBox() const = 0;
Expand Down
6 changes: 5 additions & 1 deletion include/ignition/rendering/base/BaseCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ namespace ignition
protected: math::Matrix4d projectionMatrix;

/// \brief Camera projection type
protected: CameraProjectionType projectionType;
protected: CameraProjectionType projectionType = CPT_PERSPECTIVE;

friend class BaseDepthCamera<T>;
};
Expand Down Expand Up @@ -409,6 +409,10 @@ namespace ignition
this->Scene()->PreRender();
this->Render();
this->PostRender();
if (!this->Scene()->LegacyAutoGpuFlush())
{
this->Scene()->PostRender();
}
}

//////////////////////////////////////////////////
Expand Down
Loading

0 comments on commit b68668f

Please sign in to comment.