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 hpp-fcl.
5 // hpp-fcl 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 // hpp-fcl 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 // hpp-fcl. If not, see <http://www.gnu.org/licenses/>.
16 
18 
20 
21 namespace hpp {
22 namespace fcl {
23 namespace details {
24 
25 template <typename NT>
27  const Transform3f& pose,
28  const AABB& aabb) {
29  // Ensure AABB is already computed
30  if (model->aabb_radius < 0)
31  HPP_FCL_THROW_PRETTY("Collision geometry AABB should be computed first.",
32  std::invalid_argument);
33  AABB objAabb = rotate(translate(model->aabb_local, pose.getTranslation()),
34  pose.getRotation());
35  if (!objAabb.overlap(aabb)) {
36  // No intersection.
37  return nullptr;
38  }
39  const BVHModel<NT>* m = static_cast<const BVHModel<NT>*>(model);
40  return BVHExtract(*m, pose, aabb);
41 }
42 
44  const Transform3f& pose, const AABB& aabb) {
45  switch (model->getNodeType()) {
46  case BV_AABB:
47  return extractBVHtpl<AABB>(model, pose, aabb);
48  case BV_OBB:
49  return extractBVHtpl<OBB>(model, pose, aabb);
50  case BV_RSS:
51  return extractBVHtpl<RSS>(model, pose, aabb);
52  case BV_kIOS:
53  return extractBVHtpl<kIOS>(model, pose, aabb);
54  case BV_OBBRSS:
55  return extractBVHtpl<OBBRSS>(model, pose, aabb);
56  case BV_KDOP16:
57  return extractBVHtpl<KDOP<16> >(model, pose, aabb);
58  case BV_KDOP18:
59  return extractBVHtpl<KDOP<18> >(model, pose, aabb);
60  case BV_KDOP24:
61  return extractBVHtpl<KDOP<24> >(model, pose, aabb);
62  default:
63  throw std::runtime_error("Unknown type of bounding volume");
64  }
65 }
66 } // namespace details
67 
69  const Transform3f& pose, const AABB& aabb) {
70  switch (model->getObjectType()) {
71  case OT_BVH:
72  return details::extractBVH(model, pose, aabb);
73  // case OT_GEOM: return model;
74  default:
75  throw std::runtime_error(
76  "Extraction is not implemented for this type of object");
77  }
78 }
79 } // namespace fcl
80 
81 } // namespace hpp
generate_distance_plot.m
float m
Definition: generate_distance_plot.py:6
hpp::fcl::AABB::overlap
bool overlap(const AABB &other) const
Check whether two AABB are overlap.
Definition: BV/AABB.h:110
hpp::fcl::BV_KDOP24
@ BV_KDOP24
Definition: collision_object.h:74
hpp::fcl::extract
HPP_FCL_DLLAPI CollisionGeometry * extract(const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb)
Definition: collision_utility.cpp:68
hpp::fcl::BV_RSS
@ BV_RSS
Definition: collision_object.h:69
hpp::fcl::BV_OBB
@ BV_OBB
Definition: collision_object.h:68
hpp::fcl::CollisionGeometry::getObjectType
virtual OBJECT_TYPE getObjectType() const
get the type of the object
Definition: collision_object.h:128
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::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
hpp::fcl::details::extractBVH
CollisionGeometry * extractBVH(const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb)
Definition: collision_utility.cpp:43
hpp::fcl::OT_BVH
@ OT_BVH
Definition: collision_object.h:55
hpp::fcl::details::BVHExtract
BVHModel< BV > * BVHExtract(const BVHModel< BV > &model, const Transform3f &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
hpp::fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_object.h:71
hpp::fcl::BV_AABB
@ BV_AABB
Definition: collision_object.h:67
details
Definition: traversal_node_setup.h:792
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
hpp::fcl::rotate
static AABB rotate(const AABB &aabb, const Matrix3f &R)
Definition: BV/AABB.h:233
hpp::fcl::details::extractBVHtpl
CollisionGeometry * extractBVHtpl(const CollisionGeometry *model, const Transform3f &pose, const AABB &aabb)
Definition: collision_utility.cpp:26
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::Transform3f::getTranslation
const Vec3f & getTranslation() const
get translation
Definition: transform.h:100
HPP_FCL_THROW_PRETTY
#define HPP_FCL_THROW_PRETTY(message, exception)
Definition: include/hpp/fcl/fwd.hh:57
hpp::fcl::Transform3f::getRotation
const Matrix3f & getRotation() const
get rotation
Definition: transform.h:109
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH/BVH_model.h:273
hpp::fcl::BV_KDOP18
@ BV_KDOP18
Definition: collision_object.h:73
hpp::fcl::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: collision_object.h:131
BVH_utility.h
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::BV_KDOP16
@ BV_KDOP16
Definition: collision_object.h:72
collision_utility.h
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
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13