Go to the documentation of this file.
   38 #ifndef FCL_COLLISION_OBJECT_INL_H 
   39 #define FCL_COLLISION_OBJECT_INL_H 
   54   : cgeom(cgeom_), cgeom_const(cgeom_), t(
Transform3<S>::Identity())
 
   58     cgeom->computeLocalAABB();
 
   68   : cgeom(cgeom_), cgeom_const(cgeom_), t(tf)
 
   70   cgeom->computeLocalAABB();
 
   80   : cgeom(cgeom_), cgeom_const(cgeom_), t(
Transform3<S>::Identity())
 
   84   cgeom->computeLocalAABB();
 
   99   return cgeom->getObjectType();
 
  103 template <
typename S>
 
  106   return cgeom->getNodeType();
 
  110 template <
typename S>
 
  117 template <
typename S>
 
  120   if(t.linear().isIdentity())
 
  128     aabb.min_ = center - delta;
 
  129     aabb.max_ = center + delta;
 
  134 template <
typename S>
 
  141 template <
typename S>
 
  148 template <
typename S>
 
  151   return t.translation();
 
  155 template <
typename S>
 
  162 template <
typename S>
 
  169 template <
typename S>
 
  176 template <
typename S>
 
  183 template <
typename S>
 
  190 template <
typename S>
 
  193   t.linear() = q.toRotationMatrix();
 
  197 template <
typename S>
 
  205 template <
typename S>
 
  213 template <
typename S>
 
  220 template <
typename S>
 
  223   return t.matrix().isIdentity();
 
  227 template <
typename S>
 
  234 template <
typename S>
 
  241 template <
typename S>
 
  242 const std::shared_ptr<const CollisionGeometry<S>>&
 
  249 template <
typename S>
 
  252   return cgeom->cost_density;
 
  256 template <
typename S>
 
  259   cgeom->cost_density = c;
 
  263 template <
typename S>
 
  266   return cgeom->isOccupied();
 
  270 template <
typename S>
 
  273   return cgeom->isFree();
 
  277 template <
typename S>
 
  280   return cgeom->isUncertain();
 
  
void setTransform(const Matrix3< S > &R, const Vector3< S > &T)
set object's transform
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
void setIdentityTransform()
set the object in local coordinate
void computeAABB()
compute the AABB in world space
S getCostDensity() const
get object's cost density
const Quaternion< S > getQuatRotation() const
get quaternion rotation of the object
Eigen::Quaternion< S > Quaternion
bool isUncertain() const
whether the object is uncertain
AABB< S > translate(const AABB< S > &aabb, const Eigen::MatrixBase< Derived > &t)
translate the center of AABB by t
NODE_TYPE getNodeType() const
get the node type
bool isOccupied() const
whether the object is completely occupied
OBJECT_TYPE getObjectType() const
get the type of the object
Eigen::Matrix< S, 3, 1 > Vector3
Eigen::Matrix< S, 3, 3 > Matrix3
void setRotation(const Matrix3< S > &R)
set object's rotation matrix
The geometry for the object for collision or distance computation.
const FCL_DEPRECATED CollisionGeometry< S > * getCollisionGeometry() const
get geometry from the object instance
const Matrix3< S > getRotation() const
get matrix rotation of the object
void setUserData(void *data)
set user data in object
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
CollisionObject(const std::shared_ptr< CollisionGeometry< S >> &cgeom)
void * getUserData() const
get user data in object
void setQuatRotation(const Quaternion< S > &q)
set object's quatenrion rotation
const Vector3< S > getTranslation() const
get translation of the object
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
const Transform3< S > & getTransform() const
get object's transform
template class FCL_EXPORT CollisionObject< double >
const AABB< S > & getAABB() const
get the AABB in world space
bool isIdentityTransform() const
whether the object is in local coordinate
void setCostDensity(S c)
set object's cost density
void setTranslation(const Vector3< S > &T)
set object's translation
SaPCollisionManager< S >::SaPAABB * aabb
back pointer to SAP interval
std::shared_ptr< CollisionGeometry< S > > cgeom
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
bool isFree() const
whether the object is completely free
fcl
Author(s): 
autogenerated on Fri Mar 14 2025 02:38:17