collision_utility.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017, Joseph Mirabel
2 // Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
3 //
4 // This file is part of Coal.
5 // Coal is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 //
10 // Coal is distributed in the hope that it will be
11 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
12 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13 // General Lesser Public License for more details. You should have
14 // received a copy of the GNU Lesser General Public License along with
15 // Coal. If not, see <http://www.gnu.org/licenses/>.
16 
17 #include "coal/collision_utility.h"
18 #include "coal/BVH/BVH_utility.h"
19 
20 namespace coal {
21 namespace details {
22 
23 template <typename NT>
25  const Transform3s& pose,
26  const AABB& aabb) {
27  // Ensure AABB is already computed
28  if (model->aabb_radius < 0)
29  COAL_THROW_PRETTY("Collision geometry AABB should be computed first.",
30  std::invalid_argument);
31  AABB objAabb = rotate(translate(model->aabb_local, pose.getTranslation()),
32  pose.getRotation());
33  if (!objAabb.overlap(aabb)) {
34  // No intersection.
35  return nullptr;
36  }
37  const BVHModel<NT>* m = static_cast<const BVHModel<NT>*>(model);
38  return BVHExtract(*m, pose, aabb);
39 }
40 
42  const Transform3s& pose, const AABB& aabb) {
43  switch (model->getNodeType()) {
44  case BV_AABB:
45  return extractBVHtpl<AABB>(model, pose, aabb);
46  case BV_OBB:
47  return extractBVHtpl<OBB>(model, pose, aabb);
48  case BV_RSS:
49  return extractBVHtpl<RSS>(model, pose, aabb);
50  case BV_kIOS:
51  return extractBVHtpl<kIOS>(model, pose, aabb);
52  case BV_OBBRSS:
53  return extractBVHtpl<OBBRSS>(model, pose, aabb);
54  case BV_KDOP16:
55  return extractBVHtpl<KDOP<16> >(model, pose, aabb);
56  case BV_KDOP18:
57  return extractBVHtpl<KDOP<18> >(model, pose, aabb);
58  case BV_KDOP24:
59  return extractBVHtpl<KDOP<24> >(model, pose, aabb);
60  default:
61  COAL_THROW_PRETTY("Unknown type of bounding volume", std::runtime_error);
62  }
63 }
64 } // namespace details
65 
67  const Transform3s& pose, const AABB& aabb) {
68  switch (model->getObjectType()) {
69  case OT_BVH:
70  return details::extractBVH(model, pose, aabb);
71  // case OT_GEOM: return model;
72  default:
73  COAL_THROW_PRETTY("Extraction is not implemented for this type of object",
74  std::runtime_error);
75  }
76 }
77 } // namespace coal
coal::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: coal/collision_object.h:130
generate_distance_plot.m
float m
Definition: generate_distance_plot.py:6
coal::BV_AABB
@ BV_AABB
Definition: coal/collision_object.h:66
coal::details::BVHExtract
BVHModel< BV > * BVHExtract(const BVHModel< BV > &model, const Transform3s &pose, const AABB &_aabb)
Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is con...
Definition: BVH_utility.cpp:47
coal::BV_KDOP24
@ BV_KDOP24
Definition: coal/collision_object.h:73
coal::BV_kIOS
@ BV_kIOS
Definition: coal/collision_object.h:69
coal::BV_OBBRSS
@ BV_OBBRSS
Definition: coal/collision_object.h:70
coal::OT_BVH
@ OT_BVH
Definition: coal/collision_object.h:54
coal::BV_RSS
@ BV_RSS
Definition: coal/collision_object.h:68
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::BV_KDOP18
@ BV_KDOP18
Definition: coal/collision_object.h:72
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::details::extractBVH
CollisionGeometry * extractBVH(const CollisionGeometry *model, const Transform3s &pose, const AABB &aabb)
Definition: collision_utility.cpp:41
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::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::AABB::overlap
bool overlap(const AABB &other) const
Check whether two AABB are overlap.
Definition: coal/BV/AABB.h:111
coal::extract
COAL_DLLAPI CollisionGeometry * extract(const CollisionGeometry *model, const Transform3s &pose, const AABB &aabb)
Definition: collision_utility.cpp:66
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
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::CollisionGeometry::aabb_radius
CoalScalar aabb_radius
AABB radius.
Definition: coal/collision_object.h:154
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::Transform3s::getRotation
const Matrix3s & getRotation() const
get rotation
Definition: coal/math/transform.h:110
coal::rotate
static AABB rotate(const AABB &aabb, const Matrix3s &R)
Definition: coal/BV/AABB.h:240
coal::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: coal/BVH/BVH_model.h:314
BVH_utility.h
collision_utility.h
coal::details::extractBVHtpl
CollisionGeometry * extractBVHtpl(const CollisionGeometry *model, const Transform3s &pose, const AABB &aabb)
Definition: collision_utility.cpp:24
coal::BV_OBB
@ BV_OBB
Definition: coal/collision_object.h:67
coal::BV_KDOP16
@ BV_KDOP16
Definition: coal/collision_object.h:71
coal::Transform3s::getTranslation
const Vec3s & getTranslation() const
get translation
Definition: coal/math/transform.h:101


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