38 #ifndef FCL_TRAVERSAL_MESHSHAPECOLLISIONTRAVERSALNODE_INL_H 39 #define FCL_TRAVERSAL_MESHSHAPECOLLISIONTRAVERSALNODE_INL_H 52 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
57 tri_indices =
nullptr;
63 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
68 if(this->enable_statistics) this->num_leaf_tests++;
69 const BVNode<BV>& node = this->model1->getBV(b1);
73 const Triangle& tri_id = tri_indices[primitive_id];
79 if(this->model1->isOccupied() && this->model2->isOccupied())
81 bool is_intersect =
false;
83 if(!this->request.enable_contact)
85 if(nsolver->shapeTriangleIntersect(*(this->model2), this->tf2, p1, p2, p3,
nullptr,
nullptr,
nullptr))
88 if(this->request.num_max_contacts > this->result->numContacts())
98 if(nsolver->shapeTriangleIntersect(*(this->model2), this->tf2, p1, p2, p3, &contactp, &penetration, &normal))
101 if(this->request.num_max_contacts > this->result->numContacts())
102 this->result->addContact(
Contact<S>(this->model1, this->model2, primitive_id,
Contact<S>::NONE, contactp, -normal, penetration));
106 if(is_intersect && this->request.enable_cost)
110 computeBV(*(this->model2), this->tf2, shape_aabb);
112 this->result->addCostSource(
CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
115 if((!this->model1->isFree() && !this->model2->isFree()) && this->request.enable_cost)
117 if(nsolver->shapeTriangleIntersect(*(this->model2), this->tf2, p1, p2, p3,
nullptr,
nullptr,
nullptr))
121 computeBV(*(this->model2), this->tf2, shape_aabb);
123 this->result->addCostSource(
CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
129 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
132 return this->request.isSatisfied(*(this->result));
136 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
143 const NarrowPhaseSolver* nsolver,
149 using S =
typename BV::S;
154 if(!tf1.matrix().isIdentity())
156 std::vector<Vector3<S>> vertices_transformed(model1.
num_vertices);
161 vertices_transformed[i] = new_v;
191 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver>
198 const NarrowPhaseSolver* nsolver,
199 bool enable_statistics,
200 typename BV::S cost_density,
207 using S =
typename BV::S;
209 if(enable_statistics) num_leaf_tests++;
214 const Triangle& tri_id = tri_indices[primitive_id];
220 if(model1->
isOccupied() && model2.isOccupied())
222 bool is_intersect =
false;
226 if(nsolver->shapeTriangleIntersect(model2, tf2, p1, p2, p3, tf1,
nullptr,
nullptr,
nullptr))
239 if(nsolver->shapeTriangleIntersect(model2, tf2, p1, p2, p3, tf1, &contactp, &penetration, &normal))
252 AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).
overlap(shape_aabb, overlap_part);
258 if(nsolver->shapeTriangleIntersect(model2, tf2, p1, p2, p3, tf1,
nullptr,
nullptr,
nullptr))
263 AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).
overlap(shape_aabb, overlap_part);
270 template <
typename Shape,
typename NarrowPhaseSolver>
278 template <
typename Shape,
typename NarrowPhaseSolver>
289 template <
typename Shape,
typename NarrowPhaseSolver>
297 template <
typename Shape,
typename NarrowPhaseSolver>
304 template <
typename Shape,
typename NarrowPhaseSolver>
315 template <
typename Shape,
typename NarrowPhaseSolver>
323 template <
typename Shape,
typename NarrowPhaseSolver>
331 template <
typename Shape,
typename NarrowPhaseSolver>
342 template <
typename Shape,
typename NarrowPhaseSolver>
350 template <
typename Shape,
typename NarrowPhaseSolver>
358 template <
typename Shape,
typename NarrowPhaseSolver>
368 template <
typename Shape,
typename NarrowPhaseSolver>
375 template <
typename BV,
typename Shape,
typename NarrowPhaseSolver,
376 template <
typename,
typename>
class OrientedNode>
378 OrientedNode<Shape, NarrowPhaseSolver>& node,
382 const NarrowPhaseSolver*
nsolver,
403 node.cost_density = model1.
cost_density * model2.cost_density;
409 template <
typename Shape,
typename NarrowPhaseSolver>
416 const NarrowPhaseSolver*
nsolver,
421 node,
model1, tf1, model2, tf2, nsolver, request, result);
425 template <
typename Shape,
typename NarrowPhaseSolver>
432 const NarrowPhaseSolver*
nsolver,
437 node,
model1, tf1, model2, tf2, nsolver, request, result);
441 template <
typename Shape,
typename NarrowPhaseSolver>
448 const NarrowPhaseSolver*
nsolver,
453 node,
model1, tf1, model2, tf2, nsolver, request, result);
457 template <
typename Shape,
typename NarrowPhaseSolver>
464 const NarrowPhaseSolver*
nsolver,
469 node,
model1, tf1, model2, tf2, nsolver, request, result);
Traversal node for collision between mesh and shape.
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
size_t numContacts() const
number of contacts found
bool enable_cost
If true, the cost sources will be computed.
bool enable_statistics
Whether stores statistics.
void addCostSource(const CostSource< S > &c, std::size_t num_max_cost_sources)
add one cost source into result structure
size_t num_max_contacts
The maximum number of contacts that can be returned.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
bool setupMeshShapeCollisionOrientedNode(OrientedNode< Shape, NarrowPhaseSolver > &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const Shape &model2, const Transform3< typename BV::S > &tf2, const NarrowPhaseSolver *nsolver, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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
MeshShapeCollisionTraversalNodekIOS()
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)...
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Vector3< S > * vertices
Geometry point data.
bool isFree() const
whether the object is completely free
Eigen::Matrix< S, 3, 1 > Vector3
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
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
Traversal node for collision between BVH and shape.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
const BVHModel< BV > * model1
bool enable_contact
If true, contact information (e.g., normal, penetration depth, and contact position) will be returned...
Traversal node for mesh and shape, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS)
Parameters for performing collision request.
size_t num_max_cost_sources
The maximum number of cost sources that can be returned.
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 isOccupied() const
whether the object is completely occupied
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)
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
MeshShapeCollisionTraversalNode()
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
bool initialize(MeshShapeCollisionTraversalNodeOBBRSS< Shape, NarrowPhaseSolver > &node, const BVHModel< OBBRSS< typename Shape::S >> &model1, const Transform3< typename Shape::S > &tf1, const Shape &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...
Cost source describes an area with a cost. The area is described by an AABB<S> region.
typename kIOS< Shape::S > ::S S
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.
Oriented bounding box class.
void addContact(const Contact< S > &c)
add one contact into result structure