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();
70 cgeom->computeLocalAABB();
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())
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();
const Transform3< S > & getTransform() const
get object's transform
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
void setRotation(const Matrix3< S > &R)
set object's rotation matrix
FCL_DEPRECATED const CollisionGeometry< S > * getCollisionGeometry() const
get geometry from the object instance
Eigen::Quaternion< S > Quaternion
AABB< S > aabb
AABB<S> in global coordinate.
const AABB< S > & getAABB() const
get the AABB in world space
CollisionObject(const std::shared_ptr< CollisionGeometry< S >> &cgeom)
bool isIdentityTransform() const
whether the object is in local coordinate
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
void setQuatRotation(const Quaternion< S > &q)
set object's quatenrion rotation
AABB< S > translate(const AABB< S > &aabb, const Eigen::MatrixBase< Derived > &t)
translate the center of AABB by t
void * user_data
pointer to user defined data specific to this object
bool isFree() const
whether the object is completely free
void setCostDensity(S c)
set object's cost density
void * getUserData() const
get user data in object
Eigen::Matrix< S, 3, 3 > Matrix3
const Vector3< S > getTranslation() const
get translation of the object
Vector3< S > max_
The max point in the AABB.
std::shared_ptr< CollisionGeometry< S > > cgeom
Eigen::Matrix< S, 3, 1 > Vector3
void setTranslation(const Vector3< S > &T)
set object's translation
void setTransform(const Matrix3< S > &R, const Vector3< S > &T)
set object's transform
The geometry for the object for collision or distance computation.
S getCostDensity() const
get object's cost density
void setIdentityTransform()
set the object in local coordinate
void computeAABB()
compute the AABB in world space
bool isUncertain() const
whether the object is uncertain
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Vector3< S > min_
The min point in the AABB.
const Quaternion< S > getQuatRotation() const
get quaternion rotation of the object
NODE_TYPE getNodeType() const
get the node type
template class FCL_EXPORT CollisionObject< double >
const Matrix3< S > getRotation() const
get matrix rotation of the object
std::shared_ptr< const CollisionGeometry< S > > cgeom_const
OBJECT_TYPE getObjectType() const
get the type of the object
bool isOccupied() const
whether the object is completely occupied
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry() const
get geometry from the object instance
void setUserData(void *data)
set user data in object