Go to the documentation of this file.
38 #ifndef HPP_FCL_COLLISION_OBJECT_BASE_H
39 #define HPP_FCL_COLLISION_OBJECT_BASE_H
44 #include <hpp/fcl/deprecated.hh>
98 : aabb_center(
Vec3f::Constant((std::numeric_limits<
FCL_REAL>::max)())),
101 threshold_occupied(1),
124 return isNotEqual(other);
134 virtual void computeLocalAABB() = 0;
143 inline bool isOccupied()
const {
return cost_density >= threshold_occupied; }
146 inline bool isFree()
const {
return cost_density <= threshold_free; }
149 bool isUncertain()
const;
178 return Matrix3f::Constant(NAN);
186 Matrix3f C = computeMomentofInertia();
187 Vec3f com = computeCOM();
190 return (
Matrix3f() << C(0, 0) -
V * (com[1] * com[1] + com[2] * com[2]),
191 C(0, 1) +
V * com[0] * com[1], C(0, 2) +
V * com[0] * com[2],
192 C(1, 0) +
V * com[1] * com[0],
193 C(1, 1) -
V * (com[0] * com[0] + com[2] * com[2]),
194 C(1, 2) +
V * com[1] * com[2], C(2, 0) +
V * com[2] * com[0],
195 C(2, 1) +
V * com[2] * com[1],
196 C(2, 2) -
V * (com[0] * com[0] + com[1] * com[1]))
206 return !(*
this == other);
210 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
218 bool compute_local_aabb =
true)
219 : cgeom(cgeom_), user_data(
nullptr) {
220 init(compute_local_aabb);
224 const Transform3f& tf,
bool compute_local_aabb =
true)
225 : cgeom(cgeom_),
t(tf), user_data(
nullptr) {
226 init(compute_local_aabb);
231 bool compute_local_aabb =
true)
232 : cgeom(cgeom_),
t(
R, T), user_data(
nullptr) {
233 init(compute_local_aabb);
237 return cgeom == other.
cgeom &&
t == other.
t && user_data == other.
user_data;
241 return !(*
this == other);
260 if (
t.getRotation().isIdentity()) {
261 aabb =
translate(cgeom->aabb_local,
t.getTranslation());
263 Vec3f center(
t.transform(cgeom->aabb_center));
264 Vec3f delta(Vec3f::Constant(cgeom->aabb_radius));
265 aabb.min_ = center - delta;
266 aabb.max_ = center + delta;
324 const shared_ptr<CollisionGeometry>& collision_geometry,
325 bool compute_local_aabb =
true) {
326 if (collision_geometry.get() != cgeom.get()) {
327 cgeom = collision_geometry;
328 init(compute_local_aabb);
333 void init(
bool compute_local_aabb =
true) {
335 if (compute_local_aabb) cgeom->computeLocalAABB();
340 shared_ptr<CollisionGeometry>
cgeom;
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const FCL_REAL tol=std::numeric_limits< FCL_REAL >::epsilon() *100)
virtual FCL_REAL computeVolume() const
compute the volume
void init(bool compute_local_aabb=true)
bool isIdentityTransform() const
whether the object is in local coordinate
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
bool operator!=(const CollisionObject &other) const
void setCollisionGeometry(const shared_ptr< CollisionGeometry > &collision_geometry, bool compute_local_aabb=true)
Associate a new CollisionGeometry.
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
const shared_ptr< CollisionGeometry > & collisionGeometry()
get shared pointer to collision geometry of the object instance
const CollisionGeometry * collisionGeometryPtr() const
get raw pointer to collision geometry of the object instance
void setUserData(void *data)
set user data in geometry
virtual OBJECT_TYPE getObjectType() const
get the type of the object
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
virtual Vec3f computeCOM() const
compute center of mass
The geometry for the object for collision or distance computation.
const Vec3f & getTranslation() const
get translation of the object
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
virtual Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
bool operator==(const CollisionGeometry &other) const
Equality operator.
void setTranslation(const Vec3f &T)
set object's translation
bool operator!=(const CollisionGeometry &other) const
Difference operator.
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
OBJECT_TYPE getObjectType() const
get the type of the object
void computeAABB()
compute the AABB in world space
shared_ptr< CollisionGeometry > cgeom
void * getUserData() const
get user data in geometry
CollisionGeometry * collisionGeometryPtr()
get raw pointer to collision geometry of the object instance
const Transform3f & getTransform() const
get object's transform
the object for collision or distance computation, contains the geometry and the transform information
AABB aabb
AABB in global coordinate.
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Matrix3f &R, const Vec3f &T, bool compute_local_aabb=true)
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Transform3f &tf, bool compute_local_aabb=true)
bool operator==(const CollisionObject &other) const
const Matrix3f & getRotation() const
get matrix rotation of the object
FCL_REAL threshold_occupied
threshold for occupied ( >= is occupied)
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
void setTransform(const Transform3f &tf)
set object's transform
void setIdentityTransform()
set the object in local coordinate
virtual ~CollisionGeometry()
void * user_data
pointer to user defined data specific to this object
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get shared pointer to collision geometry of the object instance
void setTransform(const Matrix3f &R, const Vec3f &T)
set object's transform
FCL_REAL cost_density
collision cost for unit volume
NODE_TYPE getNodeType() const
get the node type
void * getUserData() const
get user data in object
AABB & getAABB()
get the AABB in world space
bool isOccupied() const
whether the object is completely occupied
const AABB & getAABB() const
get the AABB in world space
virtual NODE_TYPE getNodeType() const
get the node type
virtual Matrix3f computeMomentofInertiaRelatedToCOM() const
compute the inertia matrix, related to the com
virtual bool isNotEqual(const CollisionGeometry &other) const
not equal operator with another object of derived type.
void setUserData(void *data)
set user data in object
bool isFree() const
whether the object is completely free
void setRotation(const Matrix3f &R)
set object's rotation matrix
FCL_REAL threshold_free
threshold for free (<= is free)
void * user_data
pointer to user defined data specific to this object
FCL_REAL aabb_radius
AABB radius.
static AABB translate(const AABB &aabb, const Vec3f &t)
translate the center of AABB by t
Vec3f aabb_center
AABB center in local coordinate.
hpp-fcl
Author(s):
autogenerated on Fri Aug 2 2024 02:45:13