Skip to content

Commit

Permalink
4 ➡️ 5 (#214)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina committed Jan 28, 2021
2 parents 821dd9d + 55498bf commit 5243f7e
Show file tree
Hide file tree
Showing 82 changed files with 670 additions and 255 deletions.
30 changes: 29 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,18 @@

### Ignition Rendering 4.X

### Ignition Rendering 4.X.X (20XX-XX-XX)
### Ignition Rendering 4.2.0 (2021-01-22)

1. Remove some windows warnings.
* [Pull request #183](https://github.com/ignitionrobotics/ign-rendering/pull/183)

1. Fix transparency issue for textures without alpha channel.
* [Pull request #186](https://github.com/ignitionrobotics/ign-rendering/pull/186)

1. Call XCloseDisplay in screenScalingFactor.
* [Pull request #204](https://github.com/ignitionrobotics/ign-rendering/pull/204)

1. All changes up to version 3.3.0.

### Ignition Rendering 4.1.0 (2020-11-04)

Expand Down Expand Up @@ -106,6 +117,23 @@
1. Add support for transparency based on textures alpha channel for ogre1 and ogre2
* [BitBucket pull request 229](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-rendering/pull-requests/229)

### Ignition Rendering 3.3.0 (2021-01-22)

1. Add Windows installation.
* [Pull request 196](https://github.com/ignitionrobotics/ign-rendering/pull/196)

1. Make flaky VisualAt test more verbose.
* [Pull request 174](https://github.com/ignitionrobotics/ign-rendering/pull/174)

1. Resolve updated codecheck issues.
* [Pull request 173](https://github.com/ignitionrobotics/ign-rendering/pull/173)

1. Fix crash due to NaN pose values.
* [Pull request 169](https://github.com/ignitionrobotics/ign-rendering/pull/169)

1. Improve fork experience.
* [Pull request 165](https://github.com/ignitionrobotics/ign-rendering/pull/165)

### Ignition Rendering 3.2.0 (2020-10-13)

1. Add Custom Render Engine support
Expand Down
34 changes: 2 additions & 32 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,6 @@ of libraries designed to rapidly develop robot applications.

[Usage](#usage)

[Documentation](#documentation)

[Testing](#testing)

[Folder Structure](#folder-structure)

[Code of Conduct](#code-of-conduct)
Expand All @@ -57,37 +53,11 @@ See the [installation tutorial](https://ignitionrobotics.org/api/rendering/4.0/i
# Usage

The Ign Rendering API can be found in the documentation. See the
[Documentation](#documentation) section on how to build the
documentation files using Doxygen.
[installation tutorial](https://ignitionrobotics.org/api/rendering/4.0/installation.html)
on how to build the documentation files using Doxygen.

You can also take a look at the sample applications in the `examples` folder.

# Documentation

API documentation can be generated using Doxygen

sudo apt install -y doxygen

Build documentation

cd build
make doc

View documentation

firefox doxygen/html/index.html

# Testing

Tests can be run by building the `test` target:

cd build
make test

To run tests specific to a render engine, set the `RENDER_ENGINE_VALUES` environment variable, e.g.

RENDER_ENGINE_VALUES=ogre2 make test

# Folder Structure

* `include/ignition/rendering`: Contains all the public header files which will be installed
Expand Down
2 changes: 1 addition & 1 deletion examples/actor_animation/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/camera_tracking/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
4 changes: 2 additions & 2 deletions examples/custom_scene_viewer/DemoWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,13 @@
#if defined(__APPLE__)
#include <OpenGL/gl.h>
#include <GLUT/glut.h>
#elif not defined(_WIN32)
#elif !defined(_WIN32)
#include <GL/glew.h>
#include <GL/gl.h>
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/gazebo_scene_viewer/CameraWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/mesh_viewer/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/mouse_picking/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/ogre2_demo/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/render_pass/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/simple_demo/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/text_geom/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/thermal_camera/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/transform_control/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
2 changes: 1 addition & 1 deletion examples/view_control/GlutWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <GL/glut.h>
#endif

#if not defined(__APPLE__) && not defined(_WIN32)
#if !defined(__APPLE__) && !defined(_WIN32)
#include <GL/glx.h>
#endif

Expand Down
1 change: 0 additions & 1 deletion include/ignition/rendering/MeshDescriptor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ namespace ignition
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief common::Mesh object
public: const common::Mesh *mesh = nullptr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Name of the registered Mesh
Expand Down
3 changes: 3 additions & 0 deletions include/ignition/rendering/RayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef IGNITION_RENDERING_RAYQUERY_HH_
#define IGNITION_RENDERING_RAYQUERY_HH_

#include <ignition/common/SuppressWarning.hh>
#include <ignition/math/Vector3.hh>

#include "ignition/rendering/config.hh"
Expand All @@ -37,7 +38,9 @@ namespace ignition
public: double distance = -1;

/// \brief Intersection point in 3d space
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
public: math::Vector3d point;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Intersected object id
public: unsigned int objectId = 0;
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/RenderEnginePlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <memory>
#include <string>

#include <ignition/common/SuppressWarning.hh>

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

Expand Down Expand Up @@ -52,7 +54,9 @@ namespace ignition
public: virtual RenderEngine *Engine() const = 0;

/// \brief Pointer to private data class
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
public: std::unique_ptr<RenderEnginePluginPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/RenderPassSystem.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include <string>
#include <typeinfo>

#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/config.hh"
#include "ignition/rendering/Export.hh"
#include "ignition/rendering/RenderPass.hh"
Expand Down Expand Up @@ -78,11 +80,13 @@ namespace ignition
private: RenderPassPtr CreateImpl(const std::string &_type);

/// \brief A map of render pass type id name to its factory class
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
private: static std::map<std::string, RenderPassFactory *> renderPassMap;

/// \internal
/// \brief Pointer to private data class
private: std::unique_ptr<RenderPassSystemPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};

/// \brief Render pass registration macro
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/ShaderParam.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <cstdint>
#include <memory>

#include <ignition/common/SuppressWarning.hh>

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

Expand Down Expand Up @@ -86,7 +88,9 @@ namespace ignition
public: bool Value(int *_value) const;

/// \brief private implementation
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
private: std::unique_ptr<ShaderParamPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/rendering/TransformController.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include <memory>

#include <ignition/common/SuppressWarning.hh>

#include <ignition/math/Quaternion.hh>
#include <ignition/math/Plane.hh>
#include <ignition/math/Vector3.hh>
Expand Down Expand Up @@ -210,7 +212,9 @@ namespace ignition
const math::Planed &_plane, math::Vector3d &_result);

/// \brief Private data pointer
IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
public: std::unique_ptr<TransformControllerPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
3 changes: 3 additions & 0 deletions include/ignition/rendering/base/BaseCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include <ignition/common/Event.hh>
#include <ignition/common/Console.hh>
#include <ignition/common/SuppressWarning.hh>

#include "ignition/rendering/Camera.hh"
#include "ignition/rendering/Image.hh"
Expand Down Expand Up @@ -185,6 +186,7 @@ namespace ignition

protected: virtual RenderTargetPtr RenderTarget() const = 0;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
protected: common::EventT<void(const void *, unsigned int, unsigned int,
unsigned int, const std::string &)> newFrameEvent;

Expand Down Expand Up @@ -221,6 +223,7 @@ namespace ignition

/// \brief Target node to follow
protected: NodePtr followNode;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Follow target in world frame.
protected: bool followWorldFrame = false;
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/rendering/base/BaseDepthCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace ignition
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
template <class T>
class IGNITION_RENDERING_VISIBLE BaseDepthCamera :
class BaseDepthCamera :
public virtual DepthCamera,
public virtual BaseCamera<T>,
public virtual T
Expand Down
Loading

0 comments on commit 5243f7e

Please sign in to comment.