collision_object.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef HPP_FCL_COLLISION_OBJECT_BASE_H
39 #define HPP_FCL_COLLISION_OBJECT_BASE_H
40 
41 #include <limits>
42 #include <typeinfo>
43 
44 #include <hpp/fcl/deprecated.hh>
45 #include <hpp/fcl/fwd.hh>
46 #include <hpp/fcl/BV/AABB.h>
47 #include <hpp/fcl/math/transform.h>
48 
49 namespace hpp {
50 namespace fcl {
51 
60 };
61 
65 enum NODE_TYPE {
89 };
90 
93 
95 class HPP_FCL_DLLAPI CollisionGeometry {
96  public:
98  : aabb_center(Vec3f::Constant((std::numeric_limits<FCL_REAL>::max)())),
99  aabb_radius(-1),
100  cost_density(1),
101  threshold_occupied(1),
102  threshold_free(0) {}
103 
105  CollisionGeometry(const CollisionGeometry& other) = default;
106 
107  virtual ~CollisionGeometry() {}
108 
110  virtual CollisionGeometry* clone() const = 0;
111 
113  bool operator==(const CollisionGeometry& other) const {
114  return cost_density == other.cost_density &&
115  threshold_occupied == other.threshold_occupied &&
116  threshold_free == other.threshold_free &&
117  aabb_center == other.aabb_center &&
118  aabb_radius == other.aabb_radius && aabb_local == other.aabb_local &&
119  isEqual(other);
120  }
121 
123  bool operator!=(const CollisionGeometry& other) const {
124  return isNotEqual(other);
125  }
126 
128  virtual OBJECT_TYPE getObjectType() const { return OT_UNKNOWN; }
129 
131  virtual NODE_TYPE getNodeType() const { return BV_UNKNOWN; }
132 
134  virtual void computeLocalAABB() = 0;
135 
137  void* getUserData() const { return user_data; }
138 
140  void setUserData(void* data) { user_data = data; }
141 
143  inline bool isOccupied() const { return cost_density >= threshold_occupied; }
144 
146  inline bool isFree() const { return cost_density <= threshold_free; }
147 
149  bool isUncertain() const;
150 
153 
156 
160 
162  void* user_data;
163 
166 
169 
172 
174  virtual Vec3f computeCOM() const { return Vec3f::Zero(); }
175 
178  return Matrix3f::Constant(NAN);
179  }
180 
182  virtual FCL_REAL computeVolume() const { return 0; }
183 
186  Matrix3f C = computeMomentofInertia();
187  Vec3f com = computeCOM();
188  FCL_REAL V = computeVolume();
189 
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]))
197  .finished();
198  }
199 
200  private:
202  virtual bool isEqual(const CollisionGeometry& other) const = 0;
203 
205  virtual bool isNotEqual(const CollisionGeometry& other) const {
206  return !(*this == other);
207  }
208 
209  public:
210  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
211 };
212 
215 class HPP_FCL_DLLAPI CollisionObject {
216  public:
217  CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_,
218  bool compute_local_aabb = true)
219  : cgeom(cgeom_), user_data(nullptr) {
220  init(compute_local_aabb);
221  }
222 
223  CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_,
224  const Transform3f& tf, bool compute_local_aabb = true)
225  : cgeom(cgeom_), t(tf), user_data(nullptr) {
226  init(compute_local_aabb);
227  }
228 
229  CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_,
230  const Matrix3f& R, const Vec3f& T,
231  bool compute_local_aabb = true)
232  : cgeom(cgeom_), t(R, T), user_data(nullptr) {
233  init(compute_local_aabb);
234  }
235 
236  bool operator==(const CollisionObject& other) const {
237  return cgeom == other.cgeom && t == other.t && user_data == other.user_data;
238  }
239 
240  bool operator!=(const CollisionObject& other) const {
241  return !(*this == other);
242  }
243 
245 
247  OBJECT_TYPE getObjectType() const { return cgeom->getObjectType(); }
248 
250  NODE_TYPE getNodeType() const { return cgeom->getNodeType(); }
251 
253  const AABB& getAABB() const { return aabb; }
254 
256  AABB& getAABB() { return aabb; }
257 
259  void computeAABB() {
260  if (t.getRotation().isIdentity()) {
261  aabb = translate(cgeom->aabb_local, t.getTranslation());
262  } else {
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;
267  }
268  }
269 
271  void* getUserData() const { return user_data; }
272 
274  void setUserData(void* data) { user_data = data; }
275 
277  inline const Vec3f& getTranslation() const { return t.getTranslation(); }
278 
280  inline const Matrix3f& getRotation() const { return t.getRotation(); }
281 
283  inline const Transform3f& getTransform() const { return t; }
284 
286  void setRotation(const Matrix3f& R) { t.setRotation(R); }
287 
289  void setTranslation(const Vec3f& T) { t.setTranslation(T); }
290 
292  void setTransform(const Matrix3f& R, const Vec3f& T) { t.setTransform(R, T); }
293 
295  void setTransform(const Transform3f& tf) { t = tf; }
296 
298  bool isIdentityTransform() const { return t.isIdentity(); }
299 
301  void setIdentityTransform() { t.setIdentity(); }
302 
304  const shared_ptr<const CollisionGeometry> collisionGeometry() const {
305  return cgeom;
306  }
307 
309  const shared_ptr<CollisionGeometry>& collisionGeometry() { return cgeom; }
310 
312  const CollisionGeometry* collisionGeometryPtr() const { return cgeom.get(); }
313 
315  CollisionGeometry* collisionGeometryPtr() { return cgeom.get(); }
316 
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);
329  }
330  }
331 
332  protected:
333  void init(bool compute_local_aabb = true) {
334  if (cgeom) {
335  if (compute_local_aabb) cgeom->computeLocalAABB();
336  computeAABB();
337  }
338  }
339 
340  shared_ptr<CollisionGeometry> cgeom;
341 
343 
345  mutable AABB aabb;
346 
348  void* user_data;
349 };
350 
351 } // namespace fcl
352 
353 } // namespace hpp
354 
355 #endif
hpp::fcl::isEqual
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const FCL_REAL tol=std::numeric_limits< FCL_REAL >::epsilon() *100)
Definition: tools.h:209
hpp::fcl::CollisionGeometry::computeVolume
virtual FCL_REAL computeVolume() const
compute the volume
Definition: collision_object.h:182
hpp::fcl::CollisionObject::init
void init(bool compute_local_aabb=true)
Definition: collision_object.h:333
hpp::fcl::CollisionObject::isIdentityTransform
bool isIdentityTransform() const
whether the object is in local coordinate
Definition: collision_object.h:298
hpp::fcl::HF_OBBRSS
@ HF_OBBRSS
Definition: collision_object.h:87
hpp::fcl::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: collision_object.h:82
hpp::fcl::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: collision_object.h:85
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
V
V
hpp::fcl::CollisionObject::operator!=
bool operator!=(const CollisionObject &other) const
Definition: collision_object.h:240
hpp::fcl::GEOM_BOX
@ GEOM_BOX
Definition: collision_object.h:75
hpp::fcl::OT_COUNT
@ OT_COUNT
Definition: collision_object.h:59
hpp::fcl::BV_KDOP24
@ BV_KDOP24
Definition: collision_object.h:74
hpp::fcl::GEOM_PLANE
@ GEOM_PLANE
Definition: collision_object.h:81
hpp::fcl::CollisionObject::setCollisionGeometry
void setCollisionGeometry(const shared_ptr< CollisionGeometry > &collision_geometry, bool compute_local_aabb=true)
Associate a new CollisionGeometry.
Definition: collision_object.h:323
hpp::fcl::CollisionObject::CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
Definition: collision_object.h:217
hpp::fcl::CollisionObject::collisionGeometry
const shared_ptr< CollisionGeometry > & collisionGeometry()
get shared pointer to collision geometry of the object instance
Definition: collision_object.h:309
hpp::fcl::BV_RSS
@ BV_RSS
Definition: collision_object.h:69
data
data
hpp::fcl::CollisionObject::~CollisionObject
~CollisionObject()
Definition: collision_object.h:244
hpp::fcl::OT_HFIELD
@ OT_HFIELD
Definition: collision_object.h:58
hpp::fcl::CollisionObject::collisionGeometryPtr
const CollisionGeometry * collisionGeometryPtr() const
get raw pointer to collision geometry of the object instance
Definition: collision_object.h:312
nullptr
#define nullptr
Definition: assimp.cpp:36
hpp::fcl::GEOM_CONVEX
@ GEOM_CONVEX
Definition: collision_object.h:80
hpp::fcl::BV_OBB
@ BV_OBB
Definition: collision_object.h:68
hpp::fcl::CollisionGeometry::setUserData
void setUserData(void *data)
set user data in geometry
Definition: collision_object.h:140
hpp::fcl::CollisionGeometry::getObjectType
virtual OBJECT_TYPE getObjectType() const
get the type of the object
Definition: collision_object.h:128
R
R
hpp::fcl::CollisionGeometry::aabb_local
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
Definition: collision_object.h:159
hpp::fcl::NODE_COUNT
@ NODE_COUNT
Definition: collision_object.h:88
hpp::fcl::CollisionGeometry::computeCOM
virtual Vec3f computeCOM() const
compute center of mass
Definition: collision_object.h:174
hpp::fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
hpp::fcl::CollisionObject::getTranslation
const Vec3f & getTranslation() const
get translation of the object
Definition: collision_object.h:277
hpp::fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_object.h:65
hpp::fcl::CollisionGeometry::computeMomentofInertia
virtual Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: collision_object.h:177
hpp::fcl::CollisionGeometry::operator==
bool operator==(const CollisionGeometry &other) const
Equality operator.
Definition: collision_object.h:113
hpp::fcl::CollisionObject::setTranslation
void setTranslation(const Vec3f &T)
set object's translation
Definition: collision_object.h:289
hpp::fcl::OT_BVH
@ OT_BVH
Definition: collision_object.h:55
hpp::fcl::CollisionGeometry::operator!=
bool operator!=(const CollisionGeometry &other) const
Difference operator.
Definition: collision_object.h:123
hpp::fcl::OT_GEOM
@ OT_GEOM
Definition: collision_object.h:56
hpp::fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_object.h:71
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::BV_AABB
@ BV_AABB
Definition: collision_object.h:67
hpp::fcl::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_object.h:53
hpp::fcl::CollisionObject::getObjectType
OBJECT_TYPE getObjectType() const
get the type of the object
Definition: collision_object.h:247
hpp::fcl::CollisionObject::computeAABB
void computeAABB()
compute the AABB in world space
Definition: collision_object.h:259
hpp::fcl::CollisionObject::cgeom
shared_ptr< CollisionGeometry > cgeom
Definition: collision_object.h:340
hpp::fcl::CollisionGeometry::getUserData
void * getUserData() const
get user data in geometry
Definition: collision_object.h:137
hpp::fcl::CollisionObject::collisionGeometryPtr
CollisionGeometry * collisionGeometryPtr()
get raw pointer to collision geometry of the object instance
Definition: collision_object.h:315
hpp::fcl::CollisionObject::getTransform
const Transform3f & getTransform() const
get object's transform
Definition: collision_object.h:283
hpp::fcl::GEOM_SPHERE
@ GEOM_SPHERE
Definition: collision_object.h:76
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:215
hpp::fcl::CollisionObject::aabb
AABB aabb
AABB in global coordinate.
Definition: collision_object.h:345
hpp::fcl::CollisionObject::CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Matrix3f &R, const Vec3f &T, bool compute_local_aabb=true)
Definition: collision_object.h:229
t
tuple t
hpp::fcl::CollisionObject::CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Transform3f &tf, bool compute_local_aabb=true)
Definition: collision_object.h:223
hpp::fcl::OT_OCTREE
@ OT_OCTREE
Definition: collision_object.h:57
hpp::fcl::CollisionObject::operator==
bool operator==(const CollisionObject &other) const
Definition: collision_object.h:236
hpp::fcl::CollisionObject::getRotation
const Matrix3f & getRotation() const
get matrix rotation of the object
Definition: collision_object.h:280
hpp::fcl::CollisionGeometry::threshold_occupied
FCL_REAL threshold_occupied
threshold for occupied ( >= is occupied)
Definition: collision_object.h:168
hpp::fcl::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: BV/AABB.h:54
hpp::fcl::CollisionObject::setTransform
void setTransform(const Transform3f &tf)
set object's transform
Definition: collision_object.h:295
hpp::fcl::CollisionObject::setIdentityTransform
void setIdentityTransform()
set the object in local coordinate
Definition: collision_object.h:301
hpp::fcl::GEOM_OCTREE
@ GEOM_OCTREE
Definition: collision_object.h:84
hpp::fcl::CollisionGeometry::~CollisionGeometry
virtual ~CollisionGeometry()
Definition: collision_object.h:107
hpp::fcl::CollisionGeometry::user_data
void * user_data
pointer to user defined data specific to this object
Definition: collision_object.h:162
hpp::fcl::Matrix3f
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Definition: data_types.h:68
hpp::fcl::CollisionObject::collisionGeometry
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get shared pointer to collision geometry of the object instance
Definition: collision_object.h:304
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::CollisionObject::setTransform
void setTransform(const Matrix3f &R, const Vec3f &T)
set object's transform
Definition: collision_object.h:292
hpp::fcl::CollisionGeometry::cost_density
FCL_REAL cost_density
collision cost for unit volume
Definition: collision_object.h:165
hpp::fcl::CollisionObject::getNodeType
NODE_TYPE getNodeType() const
get the node type
Definition: collision_object.h:250
hpp::fcl::CollisionObject::getUserData
void * getUserData() const
get user data in object
Definition: collision_object.h:271
hpp::fcl::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: collision_object.h:79
hpp::fcl::CollisionObject::getAABB
AABB & getAABB()
get the AABB in world space
Definition: collision_object.h:256
hpp::fcl::CollisionGeometry::isOccupied
bool isOccupied() const
whether the object is completely occupied
Definition: collision_object.h:143
hpp::fcl::BV_KDOP18
@ BV_KDOP18
Definition: collision_object.h:73
hpp::fcl::CollisionObject::getAABB
const AABB & getAABB() const
get the AABB in world space
Definition: collision_object.h:253
transform.h
hpp::fcl::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: collision_object.h:131
AABB.h
hpp::fcl::CollisionGeometry::computeMomentofInertiaRelatedToCOM
virtual Matrix3f computeMomentofInertiaRelatedToCOM() const
compute the inertia matrix, related to the com
Definition: collision_object.h:185
fwd.hh
hpp::fcl::GEOM_CONE
@ GEOM_CONE
Definition: collision_object.h:78
hpp::fcl::CollisionGeometry::isNotEqual
virtual bool isNotEqual(const CollisionGeometry &other) const
not equal operator with another object of derived type.
Definition: collision_object.h:205
hpp::fcl::CollisionObject::t
Transform3f t
Definition: collision_object.h:342
hpp::fcl::OT_UNKNOWN
@ OT_UNKNOWN
Definition: collision_object.h:54
hpp::fcl::CollisionObject::setUserData
void setUserData(void *data)
set user data in object
Definition: collision_object.h:274
hpp::fcl::CollisionGeometry::isFree
bool isFree() const
whether the object is completely free
Definition: collision_object.h:146
hpp::fcl::CollisionObject::setRotation
void setRotation(const Matrix3f &R)
set object's rotation matrix
Definition: collision_object.h:286
hpp::fcl::CollisionGeometry::threshold_free
FCL_REAL threshold_free
threshold for free (<= is free)
Definition: collision_object.h:171
hpp::fcl::CollisionObject::user_data
void * user_data
pointer to user defined data specific to this object
Definition: collision_object.h:348
hpp::fcl::BV_kIOS
@ BV_kIOS
Definition: collision_object.h:70
hpp::fcl::CollisionGeometry::aabb_radius
FCL_REAL aabb_radius
AABB radius.
Definition: collision_object.h:155
hpp::fcl::CollisionGeometry::CollisionGeometry
CollisionGeometry()
Definition: collision_object.h:97
hpp::fcl::BV_KDOP16
@ BV_KDOP16
Definition: collision_object.h:72
hpp::fcl::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: collision_object.h:77
hpp::fcl::HF_AABB
@ HF_AABB
Definition: collision_object.h:86
hpp::fcl::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: collision_object.h:83
hpp::fcl::translate
static AABB translate(const AABB &aabb, const Vec3f &t)
translate the center of AABB by t
Definition: BV/AABB.h:226
hpp::fcl::CollisionGeometry::aabb_center
Vec3f aabb_center
AABB center in local coordinate.
Definition: collision_object.h:152
hpp::fcl::BV_UNKNOWN
@ BV_UNKNOWN
Definition: collision_object.h:66


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13