From 4f4d1810eb58a9549890e2015e6122980d61f970 Mon Sep 17 00:00:00 2001 From: Joseph Mirabel <jmirabel@laas.fr> Date: Tue, 30 Aug 2016 20:30:52 +0200 Subject: [PATCH] [C++] GeometryData::computeCollision takes an index as argument --- src/algorithm/geometry.hxx | 2 +- src/multibody/geometry.hpp | 6 +++--- src/multibody/geometry.hxx | 10 ++++++---- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/src/algorithm/geometry.hxx b/src/algorithm/geometry.hxx index b5f0ae688..0edbadbc0 100644 --- a/src/algorithm/geometry.hxx +++ b/src/algorithm/geometry.hxx @@ -62,7 +62,7 @@ namespace se3 { if(data_geom.activeCollisionPairs[cpt]) { - data_geom.computeCollision(geomModel.collisionPairs[cpt],data_geom.collision_results[cpt]); + data_geom.computeCollision(cpt); isColliding |= data_geom.collision_results[cpt].isCollision(); if(isColliding && stopAtFirstCollision) return true; diff --git a/src/multibody/geometry.hpp b/src/multibody/geometry.hpp index ee4b52d6a..446c5cb77 100644 --- a/src/multibody/geometry.hpp +++ b/src/multibody/geometry.hpp @@ -270,13 +270,13 @@ namespace se3 /// /// \brief Compute the collision status between two collision objects of a given collision pair. + /// The result is store in the collision_results vector. /// - /// \param[in] pair The collsion pair. - /// \param[out] result where the collision result is stored. + /// \param[in] pairId The collsion pair index in the GeometryModel. /// /// \return Return true is the collision objects are colliding. /// - bool computeCollision(const CollisionPair & pair, fcl::CollisionResult& result) const; + bool computeCollision(const Index & pairId); /// /// \brief Compute the collision result of all the collision pairs according to diff --git a/src/multibody/geometry.hxx b/src/multibody/geometry.hxx index 60cdd0a50..7db7e9455 100644 --- a/src/multibody/geometry.hxx +++ b/src/multibody/geometry.hxx @@ -205,8 +205,11 @@ namespace se3 activeCollisionPairs[pairId] = false; } - inline bool GeometryData::computeCollision(const CollisionPair & pair, fcl::CollisionResult& collisionResult) const + inline bool GeometryData::computeCollision(const Index& pairId) { + const CollisionPair & pair = model_geom.collisionPairs[pairId]; + fcl::CollisionResult& collisionResult = collision_results[pairId]; + const Index & co1 = pair.first; assert(co1<collisionObjects.size()); const Index & co2 = pair.second; assert(co2<collisionObjects.size()); @@ -225,7 +228,7 @@ namespace se3 for(size_t i = 0; i<model_geom.collisionPairs.size(); ++i) { if(activeCollisionPairs[i]) - computeCollision(model_geom.collisionPairs[i], collision_results[i]); + computeCollision(i); } } @@ -233,8 +236,7 @@ namespace se3 { for(i = 0; i<model_geom.collisionPairs.size(); ++i) { - if (activeCollisionPairs[i] - && computeCollision(model_geom.collisionPairs[i], collision_results[i])) + if (activeCollisionPairs[i] && computeCollision(i)) return true; } return false; -- GitLab