Go to the documentation of this file.
38 #ifndef COAL_COLLISION_OBJECT_BASE_H
39 #define COAL_COLLISION_OBJECT_BASE_H
44 #include "coal/deprecated.hh"
97 : aabb_center(
Vec3s::Constant((std::numeric_limits<
CoalScalar>::max)())),
100 threshold_occupied(1),
123 return isNotEqual(other);
133 virtual void computeLocalAABB() = 0;
142 inline bool isOccupied()
const {
return cost_density >= threshold_occupied; }
145 inline bool isFree()
const {
return cost_density <= threshold_free; }
148 bool isUncertain()
const;
177 return Matrix3s::Constant(NAN);
185 Matrix3s C = computeMomentofInertia();
186 Vec3s com = computeCOM();
189 return (
Matrix3s() << C(0, 0) -
V * (com[1] * com[1] + com[2] * com[2]),
190 C(0, 1) +
V * com[0] * com[1], C(0, 2) +
V * com[0] * com[2],
191 C(1, 0) +
V * com[1] * com[0],
192 C(1, 1) -
V * (com[0] * com[0] + com[2] * com[2]),
193 C(1, 2) +
V * com[1] * com[2], C(2, 0) +
V * com[2] * com[0],
194 C(2, 1) +
V * com[2] * com[1],
195 C(2, 2) -
V * (com[0] * com[0] + com[1] * com[1]))
205 return !(*
this == other);
209 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
217 bool compute_local_aabb =
true)
218 : cgeom(cgeom_), user_data(
nullptr) {
219 init(compute_local_aabb);
223 const Transform3s& tf,
bool compute_local_aabb =
true)
224 : cgeom(cgeom_),
t(tf), user_data(
nullptr) {
225 init(compute_local_aabb);
230 bool compute_local_aabb =
true)
231 : cgeom(cgeom_),
t(
R, T), user_data(
nullptr) {
232 init(compute_local_aabb);
236 return cgeom == other.
cgeom &&
t == other.
t && user_data == other.
user_data;
240 return !(*
this == other);
259 if (
t.getRotation().isIdentity()) {
260 aabb =
translate(cgeom->aabb_local,
t.getTranslation());
262 aabb.min_ = aabb.max_ =
t.getTranslation();
264 Vec3s min_world, max_world;
265 for (
int k = 0; k < 3; ++k) {
266 min_world.array() =
t.getRotation().row(k).array() *
267 cgeom->aabb_local.min_.transpose().array();
268 max_world.array() =
t.getRotation().row(k).array() *
269 cgeom->aabb_local.max_.transpose().array();
271 aabb.min_[k] += (min_world.array().min)(max_world.array()).sum();
272 aabb.max_[k] += (min_world.array().max)(max_world.array()).sum();
331 const shared_ptr<CollisionGeometry>& collision_geometry,
332 bool compute_local_aabb =
true) {
333 if (collision_geometry.get() != cgeom.get()) {
334 cgeom = collision_geometry;
335 init(compute_local_aabb);
340 void init(
bool compute_local_aabb =
true) {
342 if (compute_local_aabb) cgeom->computeLocalAABB();
347 shared_ptr<CollisionGeometry>
cgeom;
virtual NODE_TYPE getNodeType() const
get the node type
bool isOccupied() const
whether the object is completely occupied
void init(bool compute_local_aabb=true)
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
bool operator!=(const CollisionObject &other) const
bool operator!=(const CollisionGeometry &other) const
Difference operator.
void setRotation(const Matrix3s &R)
set object's rotation matrix
const shared_ptr< CollisionGeometry > & collisionGeometry()
get shared pointer to collision geometry of the object instance
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
const Matrix3s & getRotation() const
get matrix rotation of the object
const CollisionGeometry * collisionGeometryPtr() const
get raw pointer to collision geometry of the object instance
void setTransform(const Transform3s &tf)
set object's transform
const Transform3s & getTransform() const
get object's transform
void setTransform(const Matrix3s &R, const Vec3s &T)
set object's transform
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
void computeAABB()
compute the AABB in world space
AABB & getAABB()
get the AABB in world space
CoalScalar threshold_free
threshold for free (<= is free)
The geometry for the object for collision or distance computation.
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
bool isIdentityTransform() const
whether the object is in local coordinate
virtual OBJECT_TYPE getObjectType() const
get the type of the object
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Matrix3s &R, const Vec3s &T, bool compute_local_aabb=true)
void * user_data
pointer to user defined data specific to this object
bool operator==(const CollisionGeometry &other) const
Equality operator.
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const CoalScalar tol=std::numeric_limits< CoalScalar >::epsilon() *100)
shared_ptr< CollisionGeometry > cgeom
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
OBJECT_TYPE getObjectType() const
get the type of the object
virtual Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
CoalScalar aabb_radius
AABB radius.
the object for collision or distance computation, contains the geometry and the transform information
virtual ~CollisionGeometry()
virtual CoalScalar computeVolume() const
compute the volume
CoalScalar threshold_occupied
threshold for occupied ( >= is occupied)
static AABB translate(const AABB &aabb, const Vec3s &t)
translate the center of AABB by t
CollisionGeometry * collisionGeometryPtr()
get raw pointer to collision geometry of the object instance
void setCollisionGeometry(const shared_ptr< CollisionGeometry > &collision_geometry, bool compute_local_aabb=true)
Associate a new CollisionGeometry.
const AABB & getAABB() const
get the AABB in world space
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Transform3s &tf, bool compute_local_aabb=true)
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
void setIdentityTransform()
set the object in local coordinate
void * getUserData() const
get user data in object
virtual Vec3s computeCOM() const
compute center of mass
void * getUserData() const
get user data in geometry
CoalScalar cost_density
collision cost for unit volume
AABB aabb
AABB in global coordinate.
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
const Vec3s & getTranslation() const
get translation of the object
NODE_TYPE getNodeType() const
get the node type
bool isFree() const
whether the object is completely free
void * user_data
pointer to user defined data specific to this object
bool operator==(const CollisionObject &other) const
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
Vec3s aabb_center
AABB center in local coordinate.
void setTranslation(const Vec3s &T)
set object's translation
virtual Matrix3s computeMomentofInertiaRelatedToCOM() const
compute the inertia matrix, related to the com
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get shared pointer to collision geometry of the object instance
void setUserData(void *data)
set user data in geometry
hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57