Skip to content

Commit

Permalink
Merge pull request #437 from ignitionrobotics/merge_5_6_20210927
Browse files Browse the repository at this point in the history
Merge 5 -> 6
  • Loading branch information
iche033 authored Sep 28, 2021
2 parents 5c7f216 + 63a2879 commit 34d1d0a
Show file tree
Hide file tree
Showing 23 changed files with 551 additions and 63 deletions.
16 changes: 10 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ project(ignition-rendering6 VERSION 6.0.0)
# Find ignition-cmake
#============================================================================
# If you get an error at this line, you need to install ignition-cmake
find_package(ignition-cmake2 2.3 REQUIRED)
find_package(ignition-cmake2 2.8.0 REQUIRED)
set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR})

#============================================================================
Expand All @@ -22,7 +22,7 @@ ign_configure_project(VERSION_SUFFIX pre2)
#============================================================================

set(CMAKE_CXX_STANDARD 14)
option(USE_UNOFFICAL_OGRE_VERSIONS "Accept unsupported Ogre versions in the build" OFF)
option(USE_UNOFFICIAL_OGRE_VERSIONS "Accept unsupported Ogre versions in the build" OFF)

#============================================================================
# Search for project-specific dependencies
Expand Down Expand Up @@ -66,15 +66,19 @@ list(APPEND ign_ogre_components "RTShaderSystem" "Terrain" "Overlay")

# Ogre versions greater than 1.9 are not officialy supported.
# Display a warning for the users on this setup unless they provide
# USE_UNOFFICAL_OGRE_VERSIONS flag
if (NOT USE_UNOFFICAL_OGRE_VERSIONS)
ign_find_package(IgnOGRE VERSION 1.10
COMPONENTS ${ign_ogre_components})
# USE_UNOFFICIAL_OGRE_VERSIONS flag
if (NOT USE_UNOFFICIAL_OGRE_VERSIONS)
# Only for checking the ogre version
ign_find_package(IgnOGRE VERSION 1.10 QUIET)

if (OGRE_FOUND)
IGN_BUILD_WARNING("Ogre 1.x versions greater than 1.9 are not officially supported."
"The software might compile and even work but support from upstream"
"could be reduced to accepting patches for newer versions")
ign_find_package(IgnOGRE VERSION 1.10
COMPONENTS ${ign_ogre_components}
REQUIRED_BY ogre
PRIVATE_FOR ogre)
else()
# If ogre 1.10 or greater was not found, then proceed to look for 1.9.x
# versions which are offically supported
Expand Down
21 changes: 20 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -217,6 +217,25 @@

### Ignition Rendering 4.X

### Ignition Rendering 4.9.0 (2021-09-15)

1. Output warning message if a mesh with zero submeshes is created
* [Pull request #391](https://github.com/ignitionrobotics/ign-rendering/pull/391)

1. Fix particle effect randomness
* [Pull request #388](https://github.com/ignitionrobotics/ign-rendering/pull/388)

1. Fix single ray gpu lidar
* [Pull request #384](https://github.com/ignitionrobotics/ign-rendering/pull/384)

1. Use selection buffer in ray queries (ogre2)
* [Pull request #378](https://github.com/ignitionrobotics/ign-rendering/pull/378)
* [Pull request #383](https://github.com/ignitionrobotics/ign-rendering/pull/383)

1. All changes merged forward from ign-rendering3
* [Pull request #382](https://github.com/ignitionrobotics/ign-rendering/pull/382)
* [Pull request #398](https://github.com/ignitionrobotics/ign-rendering/pull/398)

### Ignition Rendering 4.8.0 (2021-06-18)

1. relax gaussian test tolerance
Expand Down Expand Up @@ -449,7 +468,7 @@
### Ignition Rendering 3.X.X (2021-XX-XX)

1. CMake warning on Ogre versions that are not officially supported.
To disable the new warning, it is enough to enable the cmake option USE_UNOFFICAL_OGRE_VERSIONS
To disable the new warning, it is enough to enable the cmake option USE_UNOFFICIAL_OGRE_VERSIONS
* [Pull request 376](https://github.com/ignitionrobotics/ign-rendering/pull/376)

### Ignition Rendering 3.5.0 (2021-05-25)
Expand Down
4 changes: 1 addition & 3 deletions ogre/src/OgreVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,8 @@ void OgreVisual::SetWireframe(bool _show)
for (unsigned int i = 0; i < this->ogreNode->numAttachedObjects();
i++)
{
Ogre::Entity *entity = nullptr;
Ogre::MovableObject *obj = this->ogreNode->getAttachedObject(i);

entity = dynamic_cast<Ogre::Entity *>(obj);
Ogre::Entity *entity = dynamic_cast<Ogre::Entity *>(obj);

if (!entity)
continue;
Expand Down
4 changes: 4 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,10 @@ namespace ignition
// Documentation inherited.
public: virtual void SetVisibilityMask(uint32_t _mask) override;

/// \brief Get the selection buffer object
/// \return the selection buffer object
public: Ogre2SelectionBuffer *SelectionBuffer() const;

// Documentation inherited.
protected: virtual RenderTargetPtr RenderTarget() const override;

Expand Down
8 changes: 8 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2RayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,14 @@ namespace ignition
// Documentation inherited
public: virtual RayQueryResult ClosestPoint();

/// \brief Get closest point by selection buffer.
/// This is executed on the GPU.
private: RayQueryResult ClosestPointBySelectionBuffer();

/// \brief Get closest point by ray triangle intersection test.
/// This is executed on the CPU.
private: RayQueryResult ClosestPointByIntersection();

/// \brief Private data pointer
private: std::unique_ptr<Ogre2RayQueryPrivate> dataPtr;

Expand Down
10 changes: 10 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2SelectionBuffer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,16 @@ namespace ignition
/// \return Returns the Ogre item at the coordinate.
public: Ogre::Item *OnSelectionClick(const int _x, const int _y);

/// \brief Perform selection operation and get ogre item and
/// point of intersection.
/// \param[in] _x X coordinate in pixels.
/// \param[in] _y Y coordinate in pixels.
/// \param[out] _item Ogre item at the coordinate.
/// \param[out] _point 3D point of intersection with the ogre item's mesh.
/// \return True if an ogre item is found, false otherwise
public: bool ExecuteQuery(const int _x, const int _y, Ogre::Item *&_item,
math::Vector3d &_point);

/// \brief Set dimension of the selection buffer
/// \param[in] _width X dimension in pixels.
/// \param[in] _height Y dimension in pixels.
Expand Down
6 changes: 6 additions & 0 deletions ogre2/src/Ogre2Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -233,6 +233,12 @@ void Ogre2Camera::SetSelectionBuffer()
this->ImageWidth(), this->ImageHeight());
}

//////////////////////////////////////////////////
Ogre2SelectionBuffer *Ogre2Camera::SelectionBuffer() const
{
return this->selectionBuffer;
}

//////////////////////////////////////////////////
VisualPtr Ogre2Camera::VisualAt(const ignition::math::Vector2i &_mousePos)
{
Expand Down
1 change: 1 addition & 0 deletions ogre2/src/Ogre2DepthCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -434,6 +434,7 @@ void Ogre2DepthCamera::CreateDepthTexture()
double projectionA = projectionAB.x;
double projectionB = projectionAB.y;
projectionB /= farPlane;

psParams->setNamedConstant("projectionParams",
Ogre::Vector2(projectionA, projectionB));
psParams->setNamedConstant("near",
Expand Down
4 changes: 4 additions & 0 deletions ogre2/src/Ogre2ParticleNoiseListener.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <string>

#include <ignition/math/Rand.hh>

#include "ignition/rendering/ogre2/Ogre2Includes.hh"
#include "ignition/rendering/ogre2/Ogre2RenderTypes.hh"
#include "ignition/rendering/ogre2/Ogre2Scene.hh"
Expand Down Expand Up @@ -84,6 +86,8 @@ void Ogre2ParticleNoiseListener::cameraPreRenderScene(
pass->getFragmentProgramParameters();
psParams->setNamedConstant("particleStddev",
static_cast<float>(particleStddev));
psParams->setNamedConstant("rnd",
static_cast<float>(ignition::math::Rand::DblUniform(0.0, 1.0)));

// get particle scatter ratio value from particle emitter user data
// and pass that to the shaders
Expand Down
78 changes: 78 additions & 0 deletions ogre2/src/Ogre2RayQuery.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "ignition/rendering/ogre2/Ogre2Conversions.hh"
#include "ignition/rendering/ogre2/Ogre2RayQuery.hh"
#include "ignition/rendering/ogre2/Ogre2Scene.hh"
#include "ignition/rendering/ogre2/Ogre2SelectionBuffer.hh"

#ifdef _MSC_VER
#pragma warning(push, 0)
Expand All @@ -42,6 +43,15 @@ class ignition::rendering::Ogre2RayQueryPrivate
{
/// \brief Ogre ray scene query object for computing intersection.
public: Ogre::RaySceneQuery *rayQuery = nullptr;

//// \brief Pointer to camera
public: Ogre2CameraPtr camera{nullptr};

/// \brief Image pos to cast the ray from
public: math::Vector2i imgPos = math::Vector2i::Zero;

/// \brief thread that ray query is created in
public: std::thread::id threadId;
};

using namespace ignition;
Expand All @@ -51,6 +61,7 @@ using namespace rendering;
Ogre2RayQuery::Ogre2RayQuery()
: dataPtr(new Ogre2RayQueryPrivate)
{
this->dataPtr->threadId = std::this_thread::get_id();
}

//////////////////////////////////////////////////
Expand All @@ -70,10 +81,77 @@ void Ogre2RayQuery::SetFromCamera(const CameraPtr &_camera,

this->origin = Ogre2Conversions::Convert(ray.getOrigin());
this->direction = Ogre2Conversions::Convert(ray.getDirection());

this->dataPtr->camera = camera;

this->dataPtr->imgPos.X() = static_cast<int>(
screenPos.X() * this->dataPtr->camera->ImageWidth());
this->dataPtr->imgPos.Y() = static_cast<int>(
screenPos.Y() * this->dataPtr->camera->ImageHeight());
}

//////////////////////////////////////////////////
RayQueryResult Ogre2RayQuery::ClosestPoint()
{
RayQueryResult result;

#ifdef __APPLE__
return this->ClosestPointByIntersection();
#else
if (!this->dataPtr->camera ||
!this->dataPtr->camera->Parent() ||
std::this_thread::get_id() != this->dataPtr->threadId)
{
// use legacy method for backward compatibility if no camera is set or
// camera is not attached in the scene tree or
// this function is called from non-rendering thread
return this->ClosestPointByIntersection();
}
else
{
// the VisualAt function is a hack to force creation of the selection
// buffer object
// todo(anyone) Make Camera::SetSelectionBuffer function public?
if (!this->dataPtr->camera->SelectionBuffer())
this->dataPtr->camera->VisualAt(math::Vector2i(0, 0));

return this->ClosestPointBySelectionBuffer();
}
#endif
}

//////////////////////////////////////////////////
RayQueryResult Ogre2RayQuery::ClosestPointBySelectionBuffer()
{
RayQueryResult result;
Ogre::Item *ogreItem = nullptr;
math::Vector3d point;
bool success = this->dataPtr->camera->SelectionBuffer()->ExecuteQuery(
this->dataPtr->imgPos.X(), this->dataPtr->imgPos.Y(), ogreItem, point);
result.distance = -1;

if (success && ogreItem)
{
if (!ogreItem->getUserObjectBindings().getUserAny().isEmpty() &&
ogreItem->getUserObjectBindings().getUserAny().getType() ==
typeid(unsigned int))
{
auto userAny = ogreItem->getUserObjectBindings().getUserAny();
double distance = this->dataPtr->camera->WorldPosition().Distance(point)
- this->dataPtr->camera->NearClipPlane();
if (!std::isinf(distance))
{
result.distance = distance;
result.point = point;
result.objectId = Ogre::any_cast<unsigned int>(userAny);
}
}
}
return result;
}

//////////////////////////////////////////////////
RayQueryResult Ogre2RayQuery::ClosestPointByIntersection()
{
RayQueryResult result;
Ogre2ScenePtr ogreScene =
Expand Down
Loading

0 comments on commit 34d1d0a

Please sign in to comment.