Commit 2c2ff317 authored by Lucile Remigy's avatar Lucile Remigy
Browse files

Merge branch 'refactoring' into devel

parents e628dc6c a0d61965
......@@ -42,7 +42,6 @@
#include <hpp/fcl/data_types.h>
#include <hpp/fcl/collision_object.h>
#include <hpp/fcl/collision_data.h>
#include <hpp/fcl/narrowphase/narrowphase.h>
namespace hpp
{
......@@ -53,21 +52,10 @@ namespace fcl
/// returning all the contact points), whether return detailed contact information (i.e., normal, contact point, depth; otherwise only contact primitive id is returned), this function
/// performs the collision between them.
/// Return value is the number of contacts generated between the two objects.
std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
const GJKSolver* nsolver,
const CollisionRequest& request,
CollisionResult& result);
std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
const CollisionGeometry* o2, const Transform3f& tf2,
const GJKSolver* nsolver_,
const CollisionRequest& request,
CollisionResult& result);
std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
const CollisionRequest& request, CollisionResult& result);
/// @copydoc collide(const CollisionObject*, const CollisionObject*, const CollisionRequest&, CollisionResult&)
std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
const CollisionGeometry* o2, const Transform3f& tf2,
const CollisionRequest& request, CollisionResult& result);
......
......@@ -40,7 +40,6 @@
#include <hpp/fcl/collision_object.h>
#include <hpp/fcl/collision_data.h>
#include <hpp/fcl/narrowphase/narrowphase.h>
namespace hpp
{
......@@ -49,18 +48,9 @@ namespace fcl
/// @brief Main distance interface: given two collision objects, and the requirements for contacts, including whether return the nearest points, this function performs the distance between them.
/// Return value is the minimum distance generated between the two objects.
FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2,
const GJKSolver* nsolver,
const DistanceRequest& request, DistanceResult& result);
FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
const CollisionGeometry* o2, const Transform3f& tf2,
const GJKSolver* nsolver_,
const DistanceRequest& request, DistanceResult& result);
FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const DistanceRequest& request, DistanceResult& result);
/// @copydoc distance(const CollisionObject*, const CollisionObject*, const DistanceRequest&, DistanceResult&)
FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
const CollisionGeometry* o2, const Transform3f& tf2,
const DistanceRequest& request, DistanceResult& result);
......
......@@ -53,14 +53,6 @@ CollisionFunctionMatrix& getCollisionFunctionLookTable()
return table;
}
std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
const GJKSolver* nsolver,
const CollisionRequest& request,
CollisionResult& result)
{
return collide(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(), nsolver, request, result);
}
// reorder collision results in the order the call has been made.
void invertResults(CollisionResult& result)
{
......@@ -134,6 +126,14 @@ std::size_t collide(const CollisionGeometry* o1, const Transform3f& tf1,
return res;
}
std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
const GJKSolver* nsolver,
const CollisionRequest& request,
CollisionResult& result)
{
return collide(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(), nsolver, request, result);
}
std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
const CollisionRequest& request, CollisionResult& result)
{
......
......@@ -52,13 +52,6 @@ DistanceFunctionMatrix& getDistanceFunctionLookTable()
return table;
}
FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const GJKSolver* nsolver,
const DistanceRequest& request, DistanceResult& result)
{
return distance(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(), nsolver,
request, result);
}
FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
const CollisionGeometry* o2, const Transform3f& tf2,
const GJKSolver* nsolver_,
......@@ -115,6 +108,12 @@ FCL_REAL distance(const CollisionGeometry* o1, const Transform3f& tf1,
return res;
}
FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const GJKSolver* nsolver,
const DistanceRequest& request, DistanceResult& result)
{
return distance(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(), nsolver,
request, result);
}
FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const DistanceRequest& request, DistanceResult& result)
{
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment