38 #ifndef FCL_TRAVERSAL_SHAPEMESHCOLLISIONTRAVERSALNODE_INL_H 39 #define FCL_TRAVERSAL_SHAPEMESHCOLLISIONTRAVERSALNODE_INL_H 52 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
58 tri_indices =
nullptr;
64 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
70 using S =
typename BV::S;
72 if(this->enable_statistics) this->num_leaf_tests++;
73 const BVNode<BV>& node = this->model2->getBV(b2);
77 const Triangle& tri_id = tri_indices[primitive_id];
83 if(this->model1->isOccupied() && this->model2->isOccupied())
85 bool is_intersect =
false;
87 if(!this->request.enable_contact)
89 if(nsolver->shapeTriangleIntersect(*(this->model1), this->tf1, p1, p2, p3,
nullptr,
nullptr,
nullptr))
92 if(this->request.num_max_contacts > this->result->numContacts())
102 if(nsolver->shapeTriangleIntersect(*(this->model1), this->tf1, p1, p2, p3, &contactp, &penetration, &normal))
105 if(this->request.num_max_contacts > this->result->numContacts())
106 this->result->addContact(
Contact<S>(this->model1, this->model2,
Contact<S>::NONE, primitive_id, contactp, normal, penetration));
110 if(is_intersect && this->request.enable_cost)
114 computeBV(*(this->model1), this->tf1, shape_aabb);
116 this->result->addCostSource(
CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
119 else if((!this->model1->isFree() && !this->model2->isFree()) && this->request.enable_cost)
121 if(nsolver->shapeTriangleIntersect(*(this->model1), this->tf1, p1, p2, p3,
nullptr,
nullptr,
nullptr))
125 computeBV(*(this->model1), this->tf1, shape_aabb);
127 this->result->addCostSource(
CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
133 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
137 return this->request.isSatisfied(*(this->result));
141 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver>
149 const NarrowPhaseSolver* nsolver,
155 using S =
typename BV::S;
160 if(!tf2.matrix().isIdentity())
162 std::vector<Vector3<S>> vertices_transformed(model2.
num_vertices);
167 vertices_transformed[i] = new_v;
197 template <
typename Shape,
typename NarrowPhaseSolver>
204 template <
typename Shape,
typename NarrowPhaseSolver>
215 template <
typename Shape,
typename NarrowPhaseSolver>
226 template <
typename Shape,
typename NarrowPhaseSolver>
233 template <
typename Shape,
typename NarrowPhaseSolver>
244 template <
typename Shape,
typename NarrowPhaseSolver>
255 template <
typename Shape,
typename NarrowPhaseSolver>
262 template <
typename Shape,
typename NarrowPhaseSolver>
273 template <
typename Shape,
typename NarrowPhaseSolver>
284 template <
typename Shape,
typename NarrowPhaseSolver>
291 template <
typename Shape,
typename NarrowPhaseSolver>
302 template <
typename Shape,
typename NarrowPhaseSolver>
312 template <
typename Shape,
typename BV,
typename NarrowPhaseSolver,
template <
typename,
typename>
class OrientedNode>
316 const NarrowPhaseSolver*
nsolver,
337 node.cost_density = model1.cost_density * model2.
cost_density;
343 template <
typename Shape,
typename NarrowPhaseSolver>
351 const NarrowPhaseSolver*
nsolver,
356 node, model1, tf1,
model2, tf2, nsolver, request, result);
360 template <
typename Shape,
typename NarrowPhaseSolver>
368 const NarrowPhaseSolver*
nsolver,
373 node, model1, tf1,
model2, tf2, nsolver, request, result);
377 template <
typename Shape,
typename NarrowPhaseSolver>
385 const NarrowPhaseSolver*
nsolver,
390 node, model1, tf1,
model2, tf2, nsolver, request, result);
394 template <
typename Shape,
typename NarrowPhaseSolver>
402 const NarrowPhaseSolver*
nsolver,
407 node, model1, tf1,
model2, tf2, nsolver, request, result);
ShapeMeshCollisionTraversalNodekIOS()
bool enable_statistics
Whether stores statistics.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
Traversal node for collision between shape and BVH.
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
BVHModelType getModelType() const
Model type described by the instance.
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
const NarrowPhaseSolver * nsolver
Transform3< BV::S > tf2
configuration of second object
bool overlap(S a1, S a2, S b1, S b2)
returns 1 if the intervals overlap, and 0 otherwise
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
Vector3< S > * vertices
Geometry point data.
Eigen::Matrix< S, 3, 1 > Vector3
int num_vertices
Number of points.
CollisionRequest< BV::S > request
request setting for collision
FCL_EXPORT void computeBV(const Shape &s, const Transform3< typename BV::S > &tf, BV &bv)
calculate a bounding volume for a shape in a specific configuration
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
const BVHModel< BV > * model2
Traversal node for collision between shape and mesh.
static bool setupShapeMeshCollisionOrientedNode(OrientedNode< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
Parameters for performing collision request.
template bool initialize(MeshCollisionTraversalNodeOBB< double > &node, const BVHModel< OBB< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBB< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result)
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
typename kIOS< Shape::S > ::S S
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
BV bv
bounding volume storing the geometry
void meshShapeCollisionOrientedNodeLeafTesting(int b1, int b2, const BVHModel< BV > *model1, const Shape &model2, Vector3< typename BV::S > *vertices, Triangle *tri_indices, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
FCL_EXPORT bool initialize(ShapeMeshCollisionTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const Shape &model1, const Transform3< typename Shape::S > &tf1, const BVHModel< OBBRSS< typename Shape::S >> &model2, const Transform3< typename Shape::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename Shape::S > &request, CollisionResult< typename Shape::S > &result)
Initialize the traversal node for collision between one mesh and one shape, specialized for OBBRSS ty...
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
BV::S cost_density
collision cost for unit volume
CollisionResult< BV::S > * result
collision result kept during the traversal iteration
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Transform3< BV::S > tf1
configuation of first object
Cost source describes an area with a cost. The area is described by an AABB<S> region.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
A class describing the kIOS collision structure, which is a set of spheres.
ShapeMeshCollisionTraversalNode()
Oriented bounding box class.
Traversal node for shape and mesh, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS)