72 FCL_REAL res = (std::numeric_limits<FCL_REAL>::max)();
81 <<
" is not yet supported.",
82 std::invalid_argument);
85 o2,
tf2, o1,
tf1, &solver, request, result);
87 if (request.enable_nearest_points) {
89 result.
o1 = result.
o2;
102 <<
" is not yet supported.",
103 std::invalid_argument);
106 o1,
tf1, o2,
tf2, &solver, request, result);
137 <<
" is not yet supported.",
138 std::invalid_argument);
154 std::swap(result.
o1, result.
o2);
173 res =
run(tf1, tf2, request, result);
176 res =
run(tf1, tf2, request, result);
request to the distance computation
support_func_guess_t cached_support_func_guess
stores the last support function vertex index, when relevant.
const char * get_node_type_name(NODE_TYPE node_type)
Returns the name associated to a NODE_TYPE.
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
const CollisionGeometry * o1
collision object 1
bool enable_cached_guess
Whether smart guess can be provided Use gjk_initial_guess instead.
Vec3f nearest_points[2]
nearest points
ComputeDistance(const CollisionGeometry *o1, const CollisionGeometry *o2)
const CollisionGeometry * o1
DistanceFunctionMatrix & getDistanceFunctionLookTable()
const Transform3f & getTransform() const
get object's transform
virtual NODE_TYPE getNodeType() const
get the node type
HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
void set(const DistanceRequest &request)
setter from a DistanceRequest
virtual OBJECT_TYPE getObjectType() const
get the type of the object
FCL_REAL operator()(const Transform3f &tf1, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result) const
This class mimics the way "boost/timer/timer.hpp" operates while using the modern std::chrono library...
CPUTimes timings
timings for the given request
bool enable_timings
enable timings when performing collision/distance request
const CollisionGeometry * o2
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get geometry from the object instance
bool enable_nearest_points
whether to return the nearest points
Vec3f cached_guess
smart guess
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, triangle), and octree
virtual FCL_REAL run(const Transform3f &tf1, const Transform3f &tf2, const DistanceRequest &request, DistanceResult &result) const
Vec3f cached_gjk_guess
stores the last GJK ray when relevant.
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
distance matrix stores the functions for distance between different types of objects and provides a u...
DistanceFunctionMatrix::DistanceFunc func
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
the object for collision or distance computation, contains the geometry and the transform information...
The geometry for the object for collision or distance computation.
support_func_guess_t support_func_cached_guess
smart guess for the support function
DistanceFunc distance_matrix[NODE_COUNT][NODE_COUNT]
each item in the distance matrix is a function to handle distance between objects of type1 and type2 ...
GJKInitialGuess gjk_initial_guess
which warm start to use for GJK
const CollisionGeometry * o2
collision object 2
#define HPP_FCL_THROW_PRETTY(message, exception)