38 #ifndef FCL_COLLISION_OBJECT_H 39 #define FCL_COLLISION_OBJECT_H 78 void* getUserData()
const;
81 void setUserData(
void *data);
114 bool isIdentityTransform()
const;
117 void setIdentityTransform();
124 const std::shared_ptr<const CollisionGeometry<S>>& collisionGeometry()
const;
127 S getCostDensity()
const;
130 void setCostDensity(S c);
133 bool isOccupied()
const;
139 bool isUncertain()
const;
143 std::shared_ptr<CollisionGeometry<S>>
cgeom;
156 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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
Eigen::Quaternion< S > Quaternion
AABB< S > aabb
AABB<S> in global coordinate.
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
void * user_data
pointer to user defined data specific to this object
Eigen::Matrix< S, 3, 3 > Matrix3
std::shared_ptr< CollisionGeometry< S > > cgeom
Eigen::Matrix< S, 3, 1 > Vector3
The geometry for the object for collision or distance computation.
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
the object for collision or distance computation, contains the geometry and the transform information...
std::shared_ptr< const CollisionGeometry< S > > cgeom_const