Skip to content

Commit

Permalink
Fix Ogre2 assertions during ray queries
Browse files Browse the repository at this point in the history
This change negatively affects performance as we now force a scene
update with each query.

Users can specify ClosestPoint(false) if they need to call this function
multiple times without modifying anything or if they know the scene is
up to date

Signed-off-by: Matias N. Goldberg <[email protected]>
  • Loading branch information
darksylinc committed Sep 18, 2021
1 parent 4bff736 commit 2b9fdaa
Show file tree
Hide file tree
Showing 6 changed files with 30 additions and 7 deletions.
17 changes: 16 additions & 1 deletion include/ignition/rendering/RayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,23 @@ namespace ignition
const math::Vector2d &_coord) = 0;

/// \brief Compute intersections
/// \param[in] _forceSceneUpdate Performance optimization hint
/// When true Ogre2 will update all derived transforms to their
/// latest to get correct results.
///
/// When false, that step is skipped. It is only safe to
/// set it to false when nothing has changed since the last
/// update (i.e. nothing moved, no new objects created).
///
/// Ogre will assert if built in Debug mode if this value
/// is set to false when it shouldn't be.
///
/// See https://ogrecave.github.io/ogre-next/api/2.2/
/// _ogre20_changes.html#AssersionCachedOutOfDate
/// for more info
/// \return A vector of intersection results
public: virtual RayQueryResult ClosestPoint() = 0;
public: virtual RayQueryResult ClosestPoint(
bool _forceSceneUpdate = true) = 0;
};
}
}
Expand Down
5 changes: 3 additions & 2 deletions include/ignition/rendering/base/BaseRayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,8 @@ namespace ignition
const math::Vector2d &_coord) override;

// Documentation inherited
public: virtual RayQueryResult ClosestPoint() override;
public: virtual RayQueryResult ClosestPoint(
bool _forceSceneUpdate = true) override;

/// \brief Ray origin
protected: math::Vector3d origin;
Expand Down Expand Up @@ -142,7 +143,7 @@ namespace ignition

//////////////////////////////////////////////////
template <class T>
RayQueryResult BaseRayQuery<T>::ClosestPoint()
RayQueryResult BaseRayQuery<T>::ClosestPoint(bool /*_forceSceneUpdate*/)
{
// TODO(anyone): implement a generic ray query here?
RayQueryResult result;
Expand Down
3 changes: 2 additions & 1 deletion ogre/include/ignition/rendering/ogre/OgreRayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@ namespace ignition
const math::Vector2d &_coord);

// Documentation inherited
public: virtual RayQueryResult ClosestPoint();
public: virtual RayQueryResult ClosestPoint(
bool _forceSceneUpdate = true);

/// \brief Get the mesh information for the given mesh.
/// \param[in] _mesh Mesh to get info about.
Expand Down
2 changes: 1 addition & 1 deletion ogre/src/OgreRayQuery.cc
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void OgreRayQuery::SetFromCamera(const CameraPtr &_camera,
}

//////////////////////////////////////////////////
RayQueryResult OgreRayQuery::ClosestPoint()
RayQueryResult OgreRayQuery::ClosestPoint(bool /*_forceSceneUpdate*/)
{
RayQueryResult result;
OgreScenePtr ogreScene = std::dynamic_pointer_cast<OgreScene>(this->Scene());
Expand Down
3 changes: 2 additions & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2RayQuery.hh
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,8 @@ namespace ignition
const math::Vector2d &_coord);

// Documentation inherited
public: virtual RayQueryResult ClosestPoint();
public: virtual RayQueryResult ClosestPoint(
bool _forceSceneUpdate = true);

/// \brief Private data pointer
private: std::unique_ptr<Ogre2RayQueryPrivate> dataPtr;
Expand Down
7 changes: 6 additions & 1 deletion ogre2/src/Ogre2RayQuery.cc
Original file line number Diff line number Diff line change
Expand Up @@ -73,14 +73,19 @@ void Ogre2RayQuery::SetFromCamera(const CameraPtr &_camera,
}

//////////////////////////////////////////////////
RayQueryResult Ogre2RayQuery::ClosestPoint()
RayQueryResult Ogre2RayQuery::ClosestPoint(bool _forceSceneUpdate)
{
RayQueryResult result;
Ogre2ScenePtr ogreScene =
std::dynamic_pointer_cast<Ogre2Scene>(this->Scene());
if (!ogreScene)
return result;

if (_forceSceneUpdate)
{
ogreScene->OgreSceneManager()->updateSceneGraph();
}

Ogre::Ray mouseRay(Ogre2Conversions::Convert(this->origin),
Ogre2Conversions::Convert(this->direction));

Expand Down

0 comments on commit 2b9fdaa

Please sign in to comment.