Skip to content

Commit

Permalink
Use selection buffer in ray queries (ogre2) (#378)
Browse files Browse the repository at this point in the history
* testing using selection buffer for rayquery

Signed-off-by: Ian Chen <[email protected]>

* remove commented out code

Signed-off-by: Ian Chen <[email protected]>

* codecheck

Signed-off-by: Ian Chen <[email protected]>

* style

Signed-off-by: Ian Chen <[email protected]>

* Use selection buffer in ray question (ogre2) - part 2 (#383)

* extend selection buffer to return depth

Signed-off-by: Ian Chen <[email protected]>

* selection buffer depth working

Signed-off-by: Ian Chen <[email protected]>

* cleanup

Signed-off-by: Ian Chen <[email protected]>

* style

Signed-off-by: Ian Chen <[email protected]>

* add check for mac

Signed-off-by: Ian Chen <[email protected]>

* Add shaders

Signed-off-by: Ian Chen <[email protected]>

* enable mac test

Signed-off-by: Ian Chen <[email protected]>

* style

Signed-off-by: Ian Chen <[email protected]>

* fix bad merge

Signed-off-by: Ian Chen <[email protected]>

* fix drag and drop

Signed-off-by: Ian Chen <[email protected]>

* fix utils test

Signed-off-by: Ian Chen <[email protected]>

* fix doxy

Signed-off-by: Ian Chen <[email protected]>

* remove comment

Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 authored Sep 15, 2021
1 parent cda2c27 commit 038317d
Show file tree
Hide file tree
Showing 8 changed files with 449 additions and 32 deletions.
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 @@ -105,6 +105,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 @@ -52,6 +52,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 @@ -62,6 +62,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 Call this to update the selection buffer contents
public: void Update();

Expand Down
6 changes: 6 additions & 0 deletions ogre2/src/Ogre2Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,12 @@ void Ogre2Camera::SetSelectionBuffer()
this->selectionBuffer = new Ogre2SelectionBuffer(this->name, this->scene);
}

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

//////////////////////////////////////////////////
VisualPtr Ogre2Camera::VisualAt(const ignition::math::Vector2i &_mousePos)
{
Expand Down
77 changes: 77 additions & 0 deletions ogre2/src/Ogre2RayQuery.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,22 @@
#include "ignition/rendering/ogre2/Ogre2Conversions.hh"
#include "ignition/rendering/ogre2/Ogre2RayQuery.hh"
#include "ignition/rendering/ogre2/Ogre2Scene.hh"
#include "ignition/rendering/ogre2/Ogre2SelectionBuffer.hh"

/// \brief Private data class for Ogre2RayQuery
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 @@ -40,6 +50,7 @@ using namespace rendering;
Ogre2RayQuery::Ogre2RayQuery()
: dataPtr(new Ogre2RayQueryPrivate)
{
this->dataPtr->threadId = std::this_thread::get_id();
}

//////////////////////////////////////////////////
Expand All @@ -59,10 +70,76 @@ 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 pointLength = point.Length();
if (!std::isinf(pointLength))
{
result.distance = pointLength;
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 038317d

Please sign in to comment.