Skip to content

Commit

Permalink
Merge branch 'main' into ahcorde/update/ogre2.2
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll committed May 4, 2021
2 parents 62bb629 + 1d27fa2 commit 032ce0f
Show file tree
Hide file tree
Showing 52 changed files with 971 additions and 496 deletions.
10 changes: 9 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,9 @@

### Ignition Rendering 5.X

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

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

1. Add ogre2 skybox support
* [Pull request #168](https://github.com/ignitionrobotics/ign-rendering/pull/168)
Expand Down Expand Up @@ -36,6 +38,7 @@

1. Added Light Intensity
* [Pull request #233](https://github.com/ignitionrobotics/ign-rendering/pull/233)
* [Pull request #284](https://github.com/ignitionrobotics/ign-rendering/pull/284)

1. Heightmap for Ogre 1
* [Pull request #180](https://github.com/ignitionrobotics/ign-rendering/pull/180)
Expand All @@ -46,6 +49,11 @@
1. Add support for lightmaps in ogre2
* [Pull request #182](https://github.com/ignitionrobotics/ign-rendering/pull/182)

1. Documentation updates
* [Pull request #288](https://github.com/ignitionrobotics/ign-rendering/pull/288)
* [Pull request #287](https://github.com/ignitionrobotics/ign-rendering/pull/287)
* [Pull request #286](https://github.com/ignitionrobotics/ign-rendering/pull/286)

### Ignition Rendering 4.X

### Ignition Rendering 4.7.0 (2021-03-17)
Expand Down
5 changes: 3 additions & 2 deletions examples/gazebo_scene_viewer/CameraWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
* limitations under the License.
*
*/
#include "CameraWindow.hh"

#if __APPLE__
#include <OpenGL/gl.h>
Expand All @@ -28,6 +27,7 @@

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

#include <gazebo/common/Console.hh>
Expand All @@ -37,6 +37,7 @@
#include <ignition/rendering/Image.hh>
#include <ignition/rendering/Scene.hh>

#include "CameraWindow.hh"
#include "SceneManager.hh"

#define KEY_ESC 27
Expand Down Expand Up @@ -166,7 +167,7 @@ void GlutKeyboard(unsigned char _key, int, int)
{
// stop transport
gazebo::transport::stop();
gazebo::transport::fini();
gazebo::transport::fini();
exit(0);
}
else if (_key == KEY_TAB)
Expand Down
23 changes: 13 additions & 10 deletions examples/gazebo_scene_viewer/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <ignition/math/Helpers.hh>

#include <ignition/rendering/Camera.hh>
#include <ignition/rendering/Capsule.hh>
#include <ignition/rendering/Scene.hh>
#include <ignition/rendering/Visual.hh>

Expand Down Expand Up @@ -1509,13 +1510,14 @@ void SubSceneManager::ProcessCone(
void SubSceneManager::ProcessCapsule(
const gazebo::msgs::Geometry & _geometryMsg, VisualPtr _parent)
{
GeometryPtr capsule = this->activeScene->CreateCapsule();
const gazebo::msgs::CapsuleGeom &capsuleMsg = _geometryMsg.capsule();
double x = 2 * capsuleMsg.radius();
double y = 2 * capsuleMsg.radius();
double z = capsuleMsg.length();
_parent->SetLocalScale(x, y, z);
_parent->AddGeometry(capsule);
// \todo(anyone) needs gazebo capsule msg
CapsulePtr capsule = this->activeScene->CreateCapsule();
// Const gazebo::msgs::CapsuleGeom &capsuleMsg = _geometryMsg.capsule();
// Double x = 2 * capsuleMsg.radius();
// Double y = 2 * capsuleMsg.radius();
// Double z = capsuleMsg.length();
// _parent->SetLocalScale(x, y, z);
_parent->AddGeometry(std::dynamic_pointer_cast<Geometry>(capsule));
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -1833,12 +1835,13 @@ void SubSceneManager::CreateGeometryFunctionMap()
this->geomFunctions[gazebo::msgs::Geometry::BOX] =
&SubSceneManager::ProcessBox;

// TODO(anyone): enable when cone protobuf msg created
// todo(anyone): enable when cone protobuf msg is created
// this->geomFunctions[gazebo::msgs::Geometry::CONE] =
// &SubSceneManager::ProcessCone;

this->geomFunctions[gazebo::msgs::Geometry::CAPSULE] =
&SubSceneManager::ProcessSphere;
// todo(anyone): enable when capsule protobuf msg is created
// this->geomFunctions[gazebo::msgs::Geometry::CAPSULE] =
// &SubSceneManager::ProcessSphere;

this->geomFunctions[gazebo::msgs::Geometry::CYLINDER] =
&SubSceneManager::ProcessCylinder;
Expand Down
4 changes: 2 additions & 2 deletions include/ignition/rendering/base/BaseLightVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -220,8 +220,8 @@ namespace ignition
{
double angles[2];
double range = 0.2;
angles[0] = range * tan(outerAngle);
angles[1] = range * tan(innerAngle);
angles[0] = range * tan(outerAngle / 2.0);
angles[1] = range * tan(innerAngle / 2.0);

unsigned int i = 0;
positions.emplace_back(ignition::math::Vector3d(0, 0, 0));
Expand Down
7 changes: 7 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,13 @@ namespace ignition
// Documentation inherited.
public: virtual unsigned int RenderTextureGLId() const override;

// Documentation inherited.
// TODO(anyone): this function should be virtual, declared in 'Camera'
// and 'BaseCamera'. We didn't do it to preserve ABI.
// Looks in commit history for '#SetShadowsNodeDefDirtyABI' to
// see changes made and revert
public: void SetShadowsNodeDefDirty();

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

Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2Capsule.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

#include "ignition/rendering/base/BaseCapsule.hh"
#include "ignition/rendering/ogre2/Ogre2Geometry.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"

namespace Ogre
{
Expand Down
13 changes: 12 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,20 @@

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

#ifdef _MSC_VER
#pragma warning(push, 0)
#endif

#include <OgreColourValue.h>
#include <OgreVector3.h>
#include <OgrePixelFormat.h>

#ifdef _MSC_VER
#pragma warning(pop)
#endif

namespace ignition
{
namespace rendering
Expand Down
27 changes: 26 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2DepthCamera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
#include <string>

#include "ignition/rendering/base/BaseDepthCamera.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2Sensor.hh"

#include "ignition/common/Event.hh"
Expand Down Expand Up @@ -74,6 +73,10 @@ namespace ignition
/// \brief Set up 1st pass material, texture, and compositor
public: virtual void CreateDepthTexture() override;

/// \brief Creates an Ogre Workspace instance. Assumes the definition
/// already and the depth texture have already been created
private: void CreateWorkspaceInstance();

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

Expand Down Expand Up @@ -119,6 +122,28 @@ namespace ignition
/// ogre camera has not been created.
public: double FarClipPlane() const override;

// Documentation inherited.
// TODO(anyone): this function should be virtual, declared in 'Camera'
// and 'BaseCamera'. We didn't do it to preserve ABI.
// Looks in commit history for '#SetShadowsNodeDefDirtyABI' to
// see changes made and revert
public: void SetShadowsNodeDefDirty();

// TODO(anyone): This fixes the pass quad material leaving dangling
// pointers when we remove the workspace, so we have to cleanup the
// material first.
// This bug was fixed in Ogre 2.2 thus the workaround should not be
// necessary there
//
// See https://github.com/ignitionrobotics/ign-rendering/
// pull/303#pullrequestreview-635228897
// Repro:
// 1.run the sensors_demo.sdf world: ign gazebo -v 4 -r sensors_demo.sdf
// 2.open Lights plugin, top right menu (3 dots) and select Lights
// 3.insert a spot light into the scene (needs to be spot light)
// 4.ign gazebo crashes
private: void RemoveWorkspaceCrashWorkaround();

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

Expand Down
14 changes: 13 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2DynamicRenderable.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,22 @@
#include <vector>

#include "ignition/rendering/ogre2/Export.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2RenderTypes.hh"
#include "ignition/rendering/Marker.hh"

#ifdef _MSC_VER
#pragma warning(push, 0)
#endif
#include <OgreHlmsPso.h>
#ifdef _MSC_VER
#pragma warning(pop)
#endif

namespace Ogre
{
class MovableObject;
}

namespace ignition
{
namespace rendering
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include <memory>

#include "ignition/rendering/base/BaseGaussianNoisePass.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2RenderPass.hh"
#include "ignition/rendering/ogre2/Export.hh"

Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2GpuRays.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
#include "ignition/rendering/RenderTypes.hh"
#include "ignition/rendering/base/BaseGpuRays.hh"
#include "ignition/rendering/ogre2/Export.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2RenderTarget.hh"
#include "ignition/rendering/ogre2/Ogre2RenderTypes.hh"
#include "ignition/rendering/ogre2/Ogre2Scene.hh"
Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2Grid.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <memory>
#include "ignition/rendering/base/BaseGrid.hh"
#include "ignition/rendering/ogre2/Ogre2Geometry.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"

namespace Ogre
{
Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include "ignition/rendering/base/BaseLidarVisual.hh"
#include "ignition/rendering/ogre2/Ogre2Visual.hh"
#include "ignition/rendering/ogre2/Ogre2Scene.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"

namespace ignition
{
Expand Down
9 changes: 8 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2Light.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,14 @@

#include "ignition/rendering/base/BaseLight.hh"
#include "ignition/rendering/ogre2/Ogre2Node.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"

#ifdef _MSC_VER
#pragma warning(push, 0)
#endif
#include <OgreLight.h>
#ifdef _MSC_VER
#pragma warning(pop)
#endif

namespace Ogre
{
Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2LightVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@

#include "ignition/rendering/base/BaseLightVisual.hh"
#include "ignition/rendering/ogre2/Ogre2Visual.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"

namespace Ogre
{
Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2Marker.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <memory>
#include "ignition/rendering/base/BaseMarker.hh"
#include "ignition/rendering/ogre2/Ogre2Geometry.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"

namespace ignition
{
Expand Down
16 changes: 15 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2Material.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,21 @@

#include "ignition/rendering/base/BaseMaterial.hh"
#include "ignition/rendering/ogre2/Ogre2Object.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"

#ifdef _MSC_VER
#pragma warning(push, 0)
#endif
#include <Hlms/Pbs/OgreHlmsPbsPrerequisites.h>
#include <OgreMaterial.h>
#ifdef _MSC_VER
#pragma warning(pop)
#endif

namespace Ogre
{
class HlmsPbsDatablock;
class HlmsUnlitDatablock;
} // namespace Ogre

namespace ignition
{
Expand Down
10 changes: 9 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2MaterialSwitcher.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,17 @@
#include <ignition/math/Color.hh>
#include "ignition/rendering/config.hh"
#include "ignition/rendering/ogre2/Export.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2RenderTypes.hh"

#ifdef _MSC_VER
#pragma warning(push, 0)
#endif
#include <OgreMaterial.h>
#include <OgreRenderTargetListener.h>
#ifdef _MSC_VER
#pragma warning(pop)
#endif

namespace ignition
{
namespace rendering
Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2RayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include <memory>

#include "ignition/rendering/base/BaseRayQuery.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2Object.hh"
#include "ignition/rendering/ogre2/Ogre2RenderTypes.hh"

Expand Down
1 change: 0 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2RenderPass.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@

#include "ignition/rendering/base/BaseRenderPass.hh"
#include "ignition/rendering/ogre2/Export.hh"
#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2Object.hh"

namespace ignition
Expand Down
Loading

0 comments on commit 032ce0f

Please sign in to comment.