38 #ifndef FCL_TRAVERSAL_MESHCOLLISIONTRAVERSALNODE_INL_H 39 #define FCL_TRAVERSAL_MESHCOLLISIONTRAVERSALNODE_INL_H 60 MeshCollisionTraversalNodeOBB<double>& node,
62 const Transform3<double>& tf1,
64 const Transform3<double>& tf2,
65 const CollisionRequest<double>& request,
66 CollisionResult<double>& result);
75 MeshCollisionTraversalNodeRSS<double>& node,
77 const Transform3<double>& tf1,
79 const Transform3<double>& tf2,
80 const CollisionRequest<double>& request,
81 CollisionResult<double>& result);
90 MeshCollisionTraversalNodekIOS<double>& node,
92 const Transform3<double>& tf1,
94 const Transform3<double>& tf2,
95 const CollisionRequest<double>& request,
96 CollisionResult<double>& result);
105 MeshCollisionTraversalNodeOBBRSS<double>& node,
107 const Transform3<double>& tf1,
109 const Transform3<double>& tf2,
110 const CollisionRequest<double>& request,
111 CollisionResult<double>& result);
114 template <
typename BV>
120 tri_indices1 =
nullptr;
121 tri_indices2 =
nullptr;
125 template <
typename BV>
128 if(this->enable_statistics) this->num_leaf_tests++;
130 const BVNode<BV>& node1 = this->model1->getBV(b1);
131 const BVNode<BV>& node2 = this->model2->getBV(b2);
136 const Triangle& tri_id1 = tri_indices1[primitive_id1];
137 const Triangle& tri_id2 = tri_indices2[primitive_id2];
146 if(this->model1->isOccupied() && this->model2->isOccupied())
148 bool is_intersect =
false;
150 if(!this->request.enable_contact)
155 if(this->result->numContacts() < this->request.num_max_contacts)
156 this->result->addContact(
Contact<S>(this->model1, this->model2, primitive_id1, primitive_id2));
163 unsigned int n_contacts;
174 if(this->request.num_max_contacts < n_contacts + this->result->numContacts())
175 n_contacts = (this->request.num_max_contacts >= this->result->numContacts()) ? (this->request.num_max_contacts - this->result->numContacts()) : 0;
177 for(
unsigned int i = 0; i < n_contacts; ++i)
179 this->result->addContact(
Contact<S>(this->model1, this->model2, primitive_id1, primitive_id2, contacts[i], normal, penetration));
184 if(is_intersect && this->request.enable_cost)
188 this->result->addCostSource(
CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
191 else if((!this->model1->isFree() && !this->model2->isFree()) && this->request.enable_cost)
197 this->result->addCostSource(
CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
203 template <
typename BV>
206 return this->request.isSatisfied(*(this->result));
210 template <
typename BV>
222 using S =
typename BV::S;
228 if(!tf1.matrix().isIdentity())
230 std::vector<Vector3<S>> vertices_transformed1(model1.
num_vertices);
235 vertices_transformed1[i] = new_v;
245 if(!tf2.matrix().isIdentity())
247 std::vector<Vector3<S>> vertices_transformed2(model2.
num_vertices);
252 vertices_transformed2[i] = new_v;
282 template <
typename S>
291 template <
typename S>
300 template <
typename S>
324 template <
typename S>
337 template <
typename S>
349 template <
typename S>
377 template <
typename S>
401 template <
typename S>
410 template <
typename S>
419 template <
typename S>
443 template <
typename S>
452 template <
typename S>
461 template <
typename S>
485 template <
typename S>
494 template <
typename S>
503 template <
typename S>
526 template <
typename BV>
545 using S =
typename BV::S;
547 if(enable_statistics) num_leaf_tests++;
555 const Triangle& tri_id1 = tri_indices1[primitive_id1];
556 const Triangle& tri_id2 = tri_indices2[primitive_id2];
567 bool is_intersect =
false;
582 unsigned int n_contacts;
597 for(
unsigned int i = 0; i < n_contacts; ++i)
599 result.
addContact(
Contact<S>(model1, model2, primitive_id1, primitive_id2, tf1 * contacts[i], tf1.linear() * normal, penetration));
623 template <
typename BV>
642 using S =
typename BV::S;
644 if(enable_statistics) num_leaf_tests++;
652 const Triangle& tri_id1 = tri_indices1[primitive_id1];
653 const Triangle& tri_id2 = tri_indices2[primitive_id2];
664 bool is_intersect =
false;
679 unsigned int n_contacts;
683 p1, p2, p3, q1, q2, q3, tf, contacts, &n_contacts, &penetration, &normal))
690 for(
unsigned int i = 0; i < n_contacts; ++i)
692 result.
addContact(
Contact<S>(model1, model2, primitive_id1, primitive_id2, tf1 * contacts[i], tf1.linear() * normal, penetration));
715 template<
typename BV,
typename OrientedNode>
742 relativeTransform(tf1.linear(), tf1.translation(), tf2.linear(), tf2.translation(), node.R, node.T);
748 template <
typename S>
763 template <
typename S>
778 template <
typename S>
793 template <
typename S>
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.
template bool obbDisjoint(const Matrix3< double > &B, const Vector3< double > &T, const Vector3< double > &a, const Vector3< double > &b)
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.
template class FCL_EXPORT RSS< double >
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...
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Transform3< BV::S > tf2
configuration of second object
Eigen::Matrix< S, 3, 3 > Matrix3
template class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS< double >
template class FCL_EXPORT MeshCollisionTraversalNodeOBB< double >
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)...
MeshCollisionTraversalNodekIOS()
template class FCL_EXPORT MeshCollisionTraversalNodeRSS< double >
Vector3< S > * vertices
Geometry point data.
bool isFree() const
whether the object is completely free
Eigen::Matrix< S, 3, 1 > Vector3
int num_vertices
Number of points.
CollisionRequest< BV::S > request
request setting for collision
const BVHModel< BV > * model1
The first BVH model.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Triangle with 3 indices for points.
bool enable_contact
If true, contact information (e.g., normal, penetration depth, and contact position) will be returned...
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)
template class FCL_EXPORT MeshCollisionTraversalNodekIOS< double >
bool isOccupied() const
whether the object is completely occupied
bool setupMeshCollisionOrientedNode(OrientedNode &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
Traversal node for collision between BVH models.
template class FCL_EXPORT kIOS< double >
Traversal node for collision between two meshes.
Vector3< S > extent
Half dimensions of OBB.
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
template class FCL_EXPORT OBB< double >
BV bv
bounding volume storing the geometry
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
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
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.
int num_bv_tests
statistical information
template class FCL_EXPORT OBBRSS< double >
FCL_EXPORT void relativeTransform(const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &t1, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &t2, Eigen::MatrixBase< DerivedC > &R, Eigen::MatrixBase< DerivedD > &t)
CCD intersect kernel among primitives.
const BVHModel< BV > * model2
The second BVH model.
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
bool initialize(MeshCollisionTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result)
Initialize traversal node for collision between two meshes, specialized for OBBRSS type...
A class describing the kIOS collision structure, which is a set of spheres.
Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB...
MeshCollisionTraversalNode()
void meshCollisionOrientedNodeLeafTesting(int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
Oriented bounding box class.
void addContact(const Contact< S > &c)
add one contact into result structure