38 #ifndef HPP_FCL_BV_NODE_H 39 #define HPP_FCL_BV_NODE_H 73 (std::numeric_limits<unsigned int>::max)())
90 inline bool isLeaf()
const {
return first_child < 0; }
98 inline int leftChild()
const {
return first_child; }
108 template <
typename BV>
117 return Base::operator==(other) && bv == other.
bv;
127 FCL_REAL& sqrDistLowerBound)
const {
128 return bv.overlap(other.
bv, request, sqrDistLowerBound);
135 return bv.distance(other.
bv,
P1,
P2);
143 static const Matrix3f id3 = Matrix3f::Identity();
148 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
unsigned int first_primitive
The start id the primitive belonging to the current node. The index is referred to the primitive_indi...
bool overlap(const BVNode &other) const
Check whether two BVNode collide.
BV bv
bounding volume storing the geometry
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Vec3f getCenter() const
Access to the center of the BV.
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
int first_child
An index for first child node or primitive If the value is positive, it is the index of the first chi...
bool operator==(const BVNode &other) const
Equality operator.
request to the collision algorithm
bool overlap(const BVNode &other, const CollisionRequest &request, FCL_REAL &sqrDistLowerBound) const
Check whether two BVNode collide.
BVNodeBase()
Default constructor.
const Matrix3f & getOrientation() const
Access to the orientation of the BV.
FCL_REAL distance(const BVNode &other, Vec3f *P1=NULL, Vec3f *P2=NULL) const
Compute the distance between two BVNode. P1 and P2, if not NULL and the underlying BV supports distan...
bool operator!=(const BVNodeBase &other) const
Difference operator.
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
int leftChild() const
Return the index of the first child. The index is referred to the bounding volume array (i...
bool isLeaf() const
Whether current node is a leaf node (i.e. contains a primitive index.
unsigned int num_primitives
The number of primitives belonging to the current node.
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
int rightChild() const
Return the index of the second child. The index is referred to the bounding volume array (i...
bool operator==(const BVNodeBase &other) const
Equality operator.
bool operator!=(const BVNode &other) const
Difference operator.
BVNodeBase encodes the tree structure for BVH.