38 #ifndef FCL_CONTINUOUS_COLLISION_OBJECT_INL_H 39 #define FCL_CONTINUOUS_COLLISION_OBJECT_INL_H 54 : cgeom(cgeom_), cgeom_const(cgeom_)
80 return cgeom->getObjectType();
87 return cgeom->getNodeType();
104 motion->getTaylorModel(R, T);
107 box = (R * p + T).getTightBound();
109 p[2] =
cgeom->aabb_local.max_[2];
110 box =
bound(box, (R * p + T).getTightBound());
112 p[1] =
cgeom->aabb_local.max_[1];
113 p[2] =
cgeom->aabb_local.min_[2];
114 box =
bound(box, (R * p + T).getTightBound());
116 p[2] =
cgeom->aabb_local.max_[2];
117 box =
bound(box, (R * p + T).getTightBound());
119 p[0] =
cgeom->aabb_local.max_[0];
120 p[1] =
cgeom->aabb_local.min_[1];
121 p[2] =
cgeom->aabb_local.min_[2];
122 box =
bound(box, (R * p + T).getTightBound());
124 p[2] =
cgeom->aabb_local.max_[2];
125 box =
bound(box, (R * p + T).getTightBound());
127 p[1] =
cgeom->aabb_local.max_[1];
128 p[2] =
cgeom->aabb_local.min_[2];
129 box =
bound(box, (R * p + T).getTightBound());
131 p[2] =
cgeom->aabb_local.max_[2];
132 box =
bound(box, (R * p + T).getTightBound());
139 template <
typename S>
146 template <
typename S>
153 template <
typename S>
160 template <
typename S>
168 template <
typename S>
169 const std::shared_ptr<const CollisionGeometry<S>>&
void * getUserData() const
get user data in object
~ContinuousCollisionObject()
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
Vector3< S > getHigh() const
OBJECT_TYPE getObjectType() const
get the type of the object
MotionBase< S > * getMotion() const
get motion from the object instance
void setUserData(void *data)
set user data in object
Vector3< S > max_
The max point in the AABB.
ContinuousCollisionObject(const std::shared_ptr< CollisionGeometry< S >> &cgeom)
Eigen::Matrix< S, 3, 1 > Vector3
std::shared_ptr< const CollisionGeometry< S > > cgeom_const
NODE_TYPE getNodeType() const
get the node type
The geometry for the object for collision or distance computation.
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
template class FCL_EXPORT ContinuousCollisionObject< double >
std::shared_ptr< CollisionGeometry< S > > cgeom
Vector3< S > getLow() const
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Vector3< S > min_
The min point in the AABB.
AABB< S > aabb
AABB<S> in the global coordinate for the motion.
void computeAABB()
compute the AABB<S> in the world space for the motion
const AABB< S > & getAABB() const
get the AABB<S> in the world space for the motion
FCL_DEPRECATED const CollisionGeometry< S > * getCollisionGeometry() const
get geometry from the object instance
template Interval< double > bound(const Interval< double > &i, double v)
std::shared_ptr< MotionBase< S > > motion
void * user_data
pointer to user defined data specific to this object