coal/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 COAL_COLLISION_OBJECT_BASE_H
39 #define COAL_COLLISION_OBJECT_BASE_H
40 
41 #include <limits>
42 #include <typeinfo>
43 
44 #include "coal/deprecated.hh"
45 #include "coal/fwd.hh"
46 #include "coal/BV/AABB.h"
47 #include "coal/math/transform.h"
48 
49 namespace coal {
50 
59 };
60 
64 enum NODE_TYPE {
88 };
89 
92 
94 class COAL_DLLAPI CollisionGeometry {
95  public:
97  : aabb_center(Vec3s::Constant((std::numeric_limits<CoalScalar>::max)())),
98  aabb_radius(-1),
99  cost_density(1),
100  threshold_occupied(1),
101  threshold_free(0) {}
102 
104  CollisionGeometry(const CollisionGeometry& other) = default;
105 
106  virtual ~CollisionGeometry() {}
107 
109  virtual CollisionGeometry* clone() const = 0;
110 
112  bool operator==(const CollisionGeometry& other) const {
113  return cost_density == other.cost_density &&
114  threshold_occupied == other.threshold_occupied &&
115  threshold_free == other.threshold_free &&
116  aabb_center == other.aabb_center &&
117  aabb_radius == other.aabb_radius && aabb_local == other.aabb_local &&
118  isEqual(other);
119  }
120 
122  bool operator!=(const CollisionGeometry& other) const {
123  return isNotEqual(other);
124  }
125 
127  virtual OBJECT_TYPE getObjectType() const { return OT_UNKNOWN; }
128 
130  virtual NODE_TYPE getNodeType() const { return BV_UNKNOWN; }
131 
133  virtual void computeLocalAABB() = 0;
134 
136  void* getUserData() const { return user_data; }
137 
139  void setUserData(void* data) { user_data = data; }
140 
142  inline bool isOccupied() const { return cost_density >= threshold_occupied; }
143 
145  inline bool isFree() const { return cost_density <= threshold_free; }
146 
148  bool isUncertain() const;
149 
152 
155 
159 
161  void* user_data;
162 
165 
168 
171 
173  virtual Vec3s computeCOM() const { return Vec3s::Zero(); }
174 
177  return Matrix3s::Constant(NAN);
178  }
179 
181  virtual CoalScalar computeVolume() const { return 0; }
182 
185  Matrix3s C = computeMomentofInertia();
186  Vec3s com = computeCOM();
187  CoalScalar V = computeVolume();
188 
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]))
196  .finished();
197  }
198 
199  private:
201  virtual bool isEqual(const CollisionGeometry& other) const = 0;
202 
204  virtual bool isNotEqual(const CollisionGeometry& other) const {
205  return !(*this == other);
206  }
207 
208  public:
209  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
210 };
211 
214 class COAL_DLLAPI CollisionObject {
215  public:
216  CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_,
217  bool compute_local_aabb = true)
218  : cgeom(cgeom_), user_data(nullptr) {
219  init(compute_local_aabb);
220  }
221 
222  CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_,
223  const Transform3s& tf, bool compute_local_aabb = true)
224  : cgeom(cgeom_), t(tf), user_data(nullptr) {
225  init(compute_local_aabb);
226  }
227 
228  CollisionObject(const shared_ptr<CollisionGeometry>& cgeom_,
229  const Matrix3s& R, const Vec3s& T,
230  bool compute_local_aabb = true)
231  : cgeom(cgeom_), t(R, T), user_data(nullptr) {
232  init(compute_local_aabb);
233  }
234 
235  bool operator==(const CollisionObject& other) const {
236  return cgeom == other.cgeom && t == other.t && user_data == other.user_data;
237  }
238 
239  bool operator!=(const CollisionObject& other) const {
240  return !(*this == other);
241  }
242 
244 
246  OBJECT_TYPE getObjectType() const { return cgeom->getObjectType(); }
247 
249  NODE_TYPE getNodeType() const { return cgeom->getNodeType(); }
250 
252  const AABB& getAABB() const { return aabb; }
253 
255  AABB& getAABB() { return aabb; }
256 
258  void computeAABB() {
259  if (t.getRotation().isIdentity()) {
260  aabb = translate(cgeom->aabb_local, t.getTranslation());
261  } else {
262  aabb.min_ = aabb.max_ = t.getTranslation();
263 
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();
270 
271  aabb.min_[k] += (min_world.array().min)(max_world.array()).sum();
272  aabb.max_[k] += (min_world.array().max)(max_world.array()).sum();
273  }
274  }
275  }
276 
278  void* getUserData() const { return user_data; }
279 
281  void setUserData(void* data) { user_data = data; }
282 
284  inline const Vec3s& getTranslation() const { return t.getTranslation(); }
285 
287  inline const Matrix3s& getRotation() const { return t.getRotation(); }
288 
290  inline const Transform3s& getTransform() const { return t; }
291 
293  void setRotation(const Matrix3s& R) { t.setRotation(R); }
294 
296  void setTranslation(const Vec3s& T) { t.setTranslation(T); }
297 
299  void setTransform(const Matrix3s& R, const Vec3s& T) { t.setTransform(R, T); }
300 
302  void setTransform(const Transform3s& tf) { t = tf; }
303 
305  bool isIdentityTransform() const { return t.isIdentity(); }
306 
308  void setIdentityTransform() { t.setIdentity(); }
309 
311  const shared_ptr<const CollisionGeometry> collisionGeometry() const {
312  return cgeom;
313  }
314 
316  const shared_ptr<CollisionGeometry>& collisionGeometry() { return cgeom; }
317 
319  const CollisionGeometry* collisionGeometryPtr() const { return cgeom.get(); }
320 
322  CollisionGeometry* collisionGeometryPtr() { return cgeom.get(); }
323 
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);
336  }
337  }
338 
339  protected:
340  void init(bool compute_local_aabb = true) {
341  if (cgeom) {
342  if (compute_local_aabb) cgeom->computeLocalAABB();
343  computeAABB();
344  }
345  }
346 
347  shared_ptr<CollisionGeometry> cgeom;
348 
350 
352  mutable AABB aabb;
353 
355  void* user_data;
356 };
357 
358 } // namespace coal
359 
360 #endif
coal::BV_UNKNOWN
@ BV_UNKNOWN
Definition: coal/collision_object.h:65
coal::OT_UNKNOWN
@ OT_UNKNOWN
Definition: coal/collision_object.h:53
coal::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: coal/collision_object.h:130
coal::CollisionGeometry::isOccupied
bool isOccupied() const
whether the object is completely occupied
Definition: coal/collision_object.h:142
coal::BV_AABB
@ BV_AABB
Definition: coal/collision_object.h:66
coal::CollisionObject::init
void init(bool compute_local_aabb=true)
Definition: coal/collision_object.h:340
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::CollisionObject::operator!=
bool operator!=(const CollisionObject &other) const
Definition: coal/collision_object.h:239
V
V
coal::BV_KDOP24
@ BV_KDOP24
Definition: coal/collision_object.h:73
coal::CollisionGeometry::operator!=
bool operator!=(const CollisionGeometry &other) const
Difference operator.
Definition: coal/collision_object.h:122
coal::CollisionObject::setRotation
void setRotation(const Matrix3s &R)
set object's rotation matrix
Definition: coal/collision_object.h:293
coal::OT_OCTREE
@ OT_OCTREE
Definition: coal/collision_object.h:56
coal::NODE_COUNT
@ NODE_COUNT
Definition: coal/collision_object.h:87
coal::CollisionObject::collisionGeometry
const shared_ptr< CollisionGeometry > & collisionGeometry()
get shared pointer to collision geometry of the object instance
Definition: coal/collision_object.h:316
coal::CollisionObject::~CollisionObject
~CollisionObject()
Definition: coal/collision_object.h:243
coal::CollisionObject::CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
Definition: coal/collision_object.h:216
coal::CollisionObject::getRotation
const Matrix3s & getRotation() const
get matrix rotation of the object
Definition: coal/collision_object.h:287
coal::BV_kIOS
@ BV_kIOS
Definition: coal/collision_object.h:69
coal::BV_OBBRSS
@ BV_OBBRSS
Definition: coal/collision_object.h:70
coal::OT_COUNT
@ OT_COUNT
Definition: coal/collision_object.h:58
coal::CollisionObject::collisionGeometryPtr
const CollisionGeometry * collisionGeometryPtr() const
get raw pointer to collision geometry of the object instance
Definition: coal/collision_object.h:319
coal::CollisionObject::setTransform
void setTransform(const Transform3s &tf)
set object's transform
Definition: coal/collision_object.h:302
coal::OT_BVH
@ OT_BVH
Definition: coal/collision_object.h:54
coal::GEOM_CONE
@ GEOM_CONE
Definition: coal/collision_object.h:77
coal::CollisionObject::getTransform
const Transform3s & getTransform() const
get object's transform
Definition: coal/collision_object.h:290
coal::GEOM_CONVEX
@ GEOM_CONVEX
Definition: coal/collision_object.h:79
coal::CollisionObject::setTransform
void setTransform(const Matrix3s &R, const Vec3s &T)
set object's transform
Definition: coal/collision_object.h:299
coal::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: coal/collision_object.h:64
data
data
coal::BV_RSS
@ BV_RSS
Definition: coal/collision_object.h:68
coal::CollisionObject::computeAABB
void computeAABB()
compute the AABB in world space
Definition: coal/collision_object.h:258
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
nullptr
#define nullptr
Definition: assimp.cpp:36
coal::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: coal/collision_object.h:76
coal::CollisionObject::getAABB
AABB & getAABB()
get the AABB in world space
Definition: coal/collision_object.h:255
coal::CollisionGeometry::threshold_free
CoalScalar threshold_free
threshold for free (<= is free)
Definition: coal/collision_object.h:170
R
R
coal::BV_KDOP18
@ BV_KDOP18
Definition: coal/collision_object.h:72
coal::GEOM_SPHERE
@ GEOM_SPHERE
Definition: coal/collision_object.h:75
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: coal/BV/AABB.h:55
coal::CollisionObject::isIdentityTransform
bool isIdentityTransform() const
whether the object is in local coordinate
Definition: coal/collision_object.h:305
coal::CollisionGeometry::getObjectType
virtual OBJECT_TYPE getObjectType() const
get the type of the object
Definition: coal/collision_object.h:127
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::HF_AABB
@ HF_AABB
Definition: coal/collision_object.h:85
transform.h
coal::GEOM_PLANE
@ GEOM_PLANE
Definition: coal/collision_object.h:80
coal::CollisionObject::CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Matrix3s &R, const Vec3s &T, bool compute_local_aabb=true)
Definition: coal/collision_object.h:228
coal::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: coal/collision_object.h:84
coal::CollisionGeometry::user_data
void * user_data
pointer to user defined data specific to this object
Definition: coal/collision_object.h:161
coal::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: coal/collision_object.h:81
coal::CollisionGeometry::operator==
bool operator==(const CollisionGeometry &other) const
Equality operator.
Definition: coal/collision_object.h:112
coal::isEqual
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const CoalScalar tol=std::numeric_limits< CoalScalar >::epsilon() *100)
Definition: coal/internal/tools.h:204
fwd.hh
coal::CollisionObject::cgeom
shared_ptr< CollisionGeometry > cgeom
Definition: coal/collision_object.h:347
coal::CollisionGeometry::aabb_local
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
Definition: coal/collision_object.h:158
coal::CollisionObject::getObjectType
OBJECT_TYPE getObjectType() const
get the type of the object
Definition: coal/collision_object.h:246
coal::CollisionObject::t
Transform3s t
Definition: coal/collision_object.h:349
coal::CollisionGeometry::computeMomentofInertia
virtual Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/collision_object.h:176
coal::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: coal/collision_object.h:82
coal::CollisionGeometry::aabb_radius
CoalScalar aabb_radius
AABB radius.
Definition: coal/collision_object.h:154
coal::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: coal/collision_object.h:214
coal::CollisionGeometry::~CollisionGeometry
virtual ~CollisionGeometry()
Definition: coal/collision_object.h:106
coal::CollisionGeometry::computeVolume
virtual CoalScalar computeVolume() const
compute the volume
Definition: coal/collision_object.h:181
coal::CollisionGeometry::threshold_occupied
CoalScalar threshold_occupied
threshold for occupied ( >= is occupied)
Definition: coal/collision_object.h:167
coal::translate
static AABB translate(const AABB &aabb, const Vec3s &t)
translate the center of AABB by t
Definition: coal/BV/AABB.h:233
coal::CollisionObject::collisionGeometryPtr
CollisionGeometry * collisionGeometryPtr()
get raw pointer to collision geometry of the object instance
Definition: coal/collision_object.h:322
coal::CollisionObject::setCollisionGeometry
void setCollisionGeometry(const shared_ptr< CollisionGeometry > &collision_geometry, bool compute_local_aabb=true)
Associate a new CollisionGeometry.
Definition: coal/collision_object.h:330
coal::CollisionObject::getAABB
const AABB & getAABB() const
get the AABB in world space
Definition: coal/collision_object.h:252
coal::CollisionObject::CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, const Transform3s &tf, bool compute_local_aabb=true)
Definition: coal/collision_object.h:222
coal::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: coal/collision_object.h:52
coal::OT_GEOM
@ OT_GEOM
Definition: coal/collision_object.h:55
coal::CollisionObject::setIdentityTransform
void setIdentityTransform()
set the object in local coordinate
Definition: coal/collision_object.h:308
coal::CollisionObject::getUserData
void * getUserData() const
get user data in object
Definition: coal/collision_object.h:278
coal::CollisionGeometry::computeCOM
virtual Vec3s computeCOM() const
compute center of mass
Definition: coal/collision_object.h:173
coal::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: coal/collision_object.h:78
coal::GEOM_OCTREE
@ GEOM_OCTREE
Definition: coal/collision_object.h:83
coal::CollisionGeometry::getUserData
void * getUserData() const
get user data in geometry
Definition: coal/collision_object.h:136
coal::CollisionGeometry::cost_density
CoalScalar cost_density
collision cost for unit volume
Definition: coal/collision_object.h:164
coal::CollisionObject::aabb
AABB aabb
AABB in global coordinate.
Definition: coal/collision_object.h:352
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::CollisionObject::getTranslation
const Vec3s & getTranslation() const
get translation of the object
Definition: coal/collision_object.h:284
coal::CollisionGeometry::CollisionGeometry
CollisionGeometry()
Definition: coal/collision_object.h:96
coal::CollisionObject::getNodeType
NODE_TYPE getNodeType() const
get the node type
Definition: coal/collision_object.h:249
coal::CollisionGeometry::isFree
bool isFree() const
whether the object is completely free
Definition: coal/collision_object.h:145
coal::CollisionObject::user_data
void * user_data
pointer to user defined data specific to this object
Definition: coal/collision_object.h:355
coal::CollisionObject::operator==
bool operator==(const CollisionObject &other) const
Definition: coal/collision_object.h:235
coal::CollisionGeometry::isNotEqual
virtual bool isNotEqual(const CollisionGeometry &other) const
not equal operator with another object of derived type.
Definition: coal/collision_object.h:204
coal::CollisionObject::setUserData
void setUserData(void *data)
set user data in object
Definition: coal/collision_object.h:281
coal::BV_OBB
@ BV_OBB
Definition: coal/collision_object.h:67
coal::CollisionGeometry::aabb_center
Vec3s aabb_center
AABB center in local coordinate.
Definition: coal/collision_object.h:151
coal::GEOM_BOX
@ GEOM_BOX
Definition: coal/collision_object.h:74
coal::HF_OBBRSS
@ HF_OBBRSS
Definition: coal/collision_object.h:86
t
dictionary t
coal::CollisionObject::setTranslation
void setTranslation(const Vec3s &T)
set object's translation
Definition: coal/collision_object.h:296
coal::OT_HFIELD
@ OT_HFIELD
Definition: coal/collision_object.h:57
coal::CollisionGeometry::computeMomentofInertiaRelatedToCOM
virtual Matrix3s computeMomentofInertiaRelatedToCOM() const
compute the inertia matrix, related to the com
Definition: coal/collision_object.h:184
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::BV_KDOP16
@ BV_KDOP16
Definition: coal/collision_object.h:71
coal::CollisionObject::collisionGeometry
const shared_ptr< const CollisionGeometry > collisionGeometry() const
get shared pointer to collision geometry of the object instance
Definition: coal/collision_object.h:311
coal::CollisionGeometry::setUserData
void setUserData(void *data)
set user data in geometry
Definition: coal/collision_object.h:139
AABB.h


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57