38 #ifndef FCL_DISTANCE_INL_H 39 #define FCL_DISTANCE_INL_H 41 #include "fcl/narrowphase/distance.h" 49 const CollisionObject<double>* o1,
50 const CollisionObject<double>* o2,
51 const DistanceRequest<double>& request,
52 DistanceResult<double>& result);
57 const CollisionGeometry<double>* o1,
const Transform3<double>& tf1,
58 const CollisionGeometry<double>* o2,
const Transform3<double>& tf2,
59 const DistanceRequest<double>& request, DistanceResult<double>& result);
62 template <
typename GJKSolver>
63 detail::DistanceFunctionMatrix<GJKSolver>& getDistanceFunctionLookTable()
65 static detail::DistanceFunctionMatrix<GJKSolver> table;
70 template <
typename NarrowPhaseSolver>
71 typename NarrowPhaseSolver::S
distance(
72 const CollisionObject<typename NarrowPhaseSolver::S>* o1,
73 const CollisionObject<typename NarrowPhaseSolver::S>* o2,
74 const NarrowPhaseSolver* nsolver,
75 const DistanceRequest<typename NarrowPhaseSolver::S>& request,
76 DistanceResult<typename NarrowPhaseSolver::S>& result)
78 return distance<NarrowPhaseSolver>(
79 o1->collisionGeometry().get(),
81 o2->collisionGeometry().get(),
89 template <
typename NarrowPhaseSolver>
90 typename NarrowPhaseSolver::S
distance(
91 const CollisionGeometry<typename NarrowPhaseSolver::S>* o1,
92 const Transform3<typename NarrowPhaseSolver::S>& tf1,
93 const CollisionGeometry<typename NarrowPhaseSolver::S>* o2,
94 const Transform3<typename NarrowPhaseSolver::S>& tf2,
95 const NarrowPhaseSolver* nsolver_,
96 const DistanceRequest<typename NarrowPhaseSolver::S>& request,
97 DistanceResult<typename NarrowPhaseSolver::S>& result)
99 using S =
typename NarrowPhaseSolver::S;
101 const NarrowPhaseSolver* nsolver = nsolver_;
103 nsolver =
new NarrowPhaseSolver();
105 const auto& looktable = getDistanceFunctionLookTable<NarrowPhaseSolver>();
108 NODE_TYPE node_type1 = o1->getNodeType();
110 NODE_TYPE node_type2 = o2->getNodeType();
112 S res = std::numeric_limits<S>::max();
114 if(object_type1 == OT_GEOM && object_type2 == OT_BVH)
116 if(!looktable.distance_matrix[node_type2][node_type1])
118 std::cerr <<
"Warning: distance function between node type " << node_type1 <<
" and node type " << node_type2 <<
" is not supported" << std::endl;
122 res = looktable.distance_matrix[node_type2][node_type1](o2, tf2, o1, tf1, nsolver, request, result);
127 if(!looktable.distance_matrix[node_type1][node_type2])
129 std::cerr <<
"Warning: distance function between node type " << node_type1 <<
" and node type " << node_type2 <<
" is not supported" << std::endl;
133 res = looktable.distance_matrix[node_type1][node_type2](o1, tf1, o2, tf2, nsolver, request, result);
144 template <
typename S>
156 return distance(o1, o2, &solver, request, result);
161 return distance(o1, o2, &solver, request, result);
169 template <
typename S>
180 return distance(o1, tf1, o2, tf2, &solver, request, result);
185 return distance(o1, tf1, o2, tf2, &solver, request, result);
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, halfspace, triangle), and octree
Definition: collision_geometry.h:54
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
distance result
Definition: distance_request.h:48
The geometry for the object for collision or distance computation.
Definition: collision_geometry.h:59
collision and distance solver based on libccd library.
Definition: gjk_solver_libccd.h:53
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_geometry.h:51
GJKSolverType gjk_solver_type
narrow phase solver type
Definition: distance_request.h:62
the object for collision or distance computation, contains the geometry and the transform information...
Definition: collision_object.h:51
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS-inl.h:266
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Definition: gjk_solver_indep.h:53
request to the distance computation
Definition: distance_request.h:52