coal/BV/AABB.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_AABB_H
39 #define COAL_AABB_H
40 
41 #include "coal/data_types.h"
42 
43 namespace coal {
44 
45 struct CollisionRequest;
46 class Plane;
47 class Halfspace;
48 
52 
55 class COAL_DLLAPI AABB {
56  public:
61 
63  AABB();
64 
66  AABB(const Vec3s& v) : min_(v), max_(v) {}
67 
69  AABB(const Vec3s& a, const Vec3s& b)
70  : min_(a.cwiseMin(b)), max_(a.cwiseMax(b)) {}
71 
73  AABB(const AABB& core, const Vec3s& delta)
74  : min_(core.min_ - delta), max_(core.max_ + delta) {}
75 
77  AABB(const Vec3s& a, const Vec3s& b, const Vec3s& c)
78  : min_(a.cwiseMin(b).cwiseMin(c)), max_(a.cwiseMax(b).cwiseMax(c)) {}
79 
80  AABB(const AABB& other) = default;
81 
82  AABB& operator=(const AABB& other) = default;
83 
84  AABB& update(const Vec3s& a, const Vec3s& b) {
85  min_ = a.cwiseMin(b);
86  max_ = a.cwiseMax(b);
87  return *this;
88  }
89 
91  bool operator==(const AABB& other) const {
92  return min_ == other.min_ && max_ == other.max_;
93  }
94 
95  bool operator!=(const AABB& other) const { return !(*this == other); }
96 
100 
102  inline bool contain(const Vec3s& p) const {
103  if (p[0] < min_[0] || p[0] > max_[0]) return false;
104  if (p[1] < min_[1] || p[1] > max_[1]) return false;
105  if (p[2] < min_[2] || p[2] > max_[2]) return false;
106 
107  return true;
108  }
109 
111  inline bool overlap(const AABB& other) const {
112  if (min_[0] > other.max_[0]) return false;
113  if (min_[1] > other.max_[1]) return false;
114  if (min_[2] > other.max_[2]) return false;
115 
116  if (max_[0] < other.min_[0]) return false;
117  if (max_[1] < other.min_[1]) return false;
118  if (max_[2] < other.min_[2]) return false;
119 
120  return true;
121  }
122 
124  bool overlap(const Plane& p) const;
125 
127  bool overlap(const Halfspace& hs) const;
128 
130  bool overlap(const AABB& other, const CollisionRequest& request,
131  CoalScalar& sqrDistLowerBound) const;
132 
134  CoalScalar distance(const AABB& other) const;
135 
138  CoalScalar distance(const AABB& other, Vec3s* P, Vec3s* Q) const;
139 
141  inline AABB& operator+=(const Vec3s& p) {
142  min_ = min_.cwiseMin(p);
143  max_ = max_.cwiseMax(p);
144  return *this;
145  }
146 
148  inline AABB& operator+=(const AABB& other) {
149  min_ = min_.cwiseMin(other.min_);
150  max_ = max_.cwiseMax(other.max_);
151  return *this;
152  }
153 
155  inline AABB operator+(const AABB& other) const {
156  AABB res(*this);
157  return res += other;
158  }
159 
161  inline CoalScalar size() const { return (max_ - min_).squaredNorm(); }
162 
164  inline Vec3s center() const { return (min_ + max_) * 0.5; }
165 
167  inline CoalScalar width() const { return max_[0] - min_[0]; }
168 
170  inline CoalScalar height() const { return max_[1] - min_[1]; }
171 
173  inline CoalScalar depth() const { return max_[2] - min_[2]; }
174 
176  inline CoalScalar volume() const { return width() * height() * depth(); }
177 
179 
181  inline bool contain(const AABB& other) const {
182  return (other.min_[0] >= min_[0]) && (other.max_[0] <= max_[0]) &&
183  (other.min_[1] >= min_[1]) && (other.max_[1] <= max_[1]) &&
184  (other.min_[2] >= min_[2]) && (other.max_[2] <= max_[2]);
185  }
186 
188  inline bool overlap(const AABB& other, AABB& overlap_part) const {
189  if (!overlap(other)) {
190  return false;
191  }
192 
193  overlap_part.min_ = min_.cwiseMax(other.min_);
194  overlap_part.max_ = max_.cwiseMin(other.max_);
195  return true;
196  }
197 
199  inline bool axisOverlap(const AABB& other, int axis_id) const {
200  if (min_[axis_id] > other.max_[axis_id]) return false;
201  if (max_[axis_id] < other.min_[axis_id]) return false;
202 
203  return true;
204  }
205 
208  inline AABB& expand(const Vec3s& delta) {
209  min_ -= delta;
210  max_ += delta;
211  return *this;
212  }
213 
216  inline AABB& expand(const CoalScalar delta) {
217  min_.array() -= delta;
218  max_.array() += delta;
219  return *this;
220  }
221 
223  inline AABB& expand(const AABB& core, CoalScalar ratio) {
224  min_ = min_ * ratio - core.min_;
225  max_ = max_ * ratio - core.max_;
226  return *this;
227  }
228 
229  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
230 };
231 
233 static inline AABB translate(const AABB& aabb, const Vec3s& t) {
234  AABB res(aabb);
235  res.min_ += t;
236  res.max_ += t;
237  return res;
238 }
239 
240 static inline AABB rotate(const AABB& aabb, const Matrix3s& R) {
241  AABB res(R * aabb.min_);
242  Vec3s corner(aabb.min_);
243  const Eigen::DenseIndex bit[3] = {1, 2, 4};
244  for (Eigen::DenseIndex ic = 1; ic < 8;
245  ++ic) { // ic = 0 corresponds to aabb.min_. Skip it.
246  for (Eigen::DenseIndex i = 0; i < 3; ++i) {
247  corner[i] = (ic & bit[i]) ? aabb.max_[i] : aabb.min_[i];
248  }
249  res += R * corner;
250  }
251  return res;
252 }
253 
256 COAL_DLLAPI bool overlap(const Matrix3s& R0, const Vec3s& T0, const AABB& b1,
257  const AABB& b2);
258 
261 COAL_DLLAPI bool overlap(const Matrix3s& R0, const Vec3s& T0, const AABB& b1,
262  const AABB& b2, const CollisionRequest& request,
263  CoalScalar& sqrDistLowerBound);
264 } // namespace coal
265 
266 #endif
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::AABB::expand
AABB & expand(const CoalScalar delta)
expand the half size of the AABB by a scalar delta, and keep the center unchanged.
Definition: coal/BV/AABB.h:216
coal::AABB::operator+=
AABB & operator+=(const Vec3s &p)
Merge the AABB and a point.
Definition: coal/BV/AABB.h:141
coal::Halfspace
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
Definition: coal/shape/geometric_shapes.h:892
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::AABB::width
CoalScalar width() const
Width of the AABB.
Definition: coal/BV/AABB.h:167
R
R
coal::distance
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:180
coal::AABB::operator!=
bool operator!=(const AABB &other) const
Definition: coal/BV/AABB.h:95
coal::AABB::depth
CoalScalar depth() const
Depth of the AABB.
Definition: coal/BV/AABB.h:173
coal::AABB::overlap
bool overlap(const AABB &other, AABB &overlap_part) const
Check whether two AABB are overlap and return the overlap part.
Definition: coal/BV/AABB.h:188
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::Plane
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
Definition: coal/shape/geometric_shapes.h:983
a
list a
coal::AABB::height
CoalScalar height() const
Height of the AABB.
Definition: coal/BV/AABB.h:170
coal::AABB::max_
Vec3s max_
The max point in the AABB.
Definition: coal/BV/AABB.h:60
coal::AABB::update
AABB & update(const Vec3s &a, const Vec3s &b)
Definition: coal/BV/AABB.h:84
res
res
coal::AABB::overlap
bool overlap(const AABB &other) const
Check whether two AABB are overlap.
Definition: coal/BV/AABB.h:111
coal::AABB::volume
CoalScalar volume() const
Volume of the AABB.
Definition: coal/BV/AABB.h:176
c
c
coal::AABB::expand
AABB & expand(const AABB &core, CoalScalar ratio)
expand the aabb by increase the thickness of the plate by a ratio
Definition: coal/BV/AABB.h:223
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
coal::AABB::AABB
AABB(const Vec3s &a, const Vec3s &b, const Vec3s &c)
Creating an AABB contains three points.
Definition: coal/BV/AABB.h:77
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::AABB::contain
bool contain(const Vec3s &p) const
Check whether the AABB contains a point.
Definition: coal/BV/AABB.h:102
coal::AABB::center
Vec3s center() const
Center of the AABB.
Definition: coal/BV/AABB.h:164
coal::AABB::contain
bool contain(const AABB &other) const
Check whether the AABB contains another AABB.
Definition: coal/BV/AABB.h:181
coal::overlap
COAL_DLLAPI bool overlap(const Matrix3s &R0, const Vec3s &T0, const AABB &b1, const AABB &b2)
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity.
Definition: AABB.cpp:134
coal::AABB::min_
Vec3s min_
The min point in the AABB.
Definition: coal/BV/AABB.h:58
coal::AABB::operator+
AABB operator+(const AABB &other) const
Return the merged AABB of current AABB and the other one.
Definition: coal/BV/AABB.h:155
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::rotate
static AABB rotate(const AABB &aabb, const Matrix3s &R)
Definition: coal/BV/AABB.h:240
coal::AABB::operator+=
AABB & operator+=(const AABB &other)
Merge the AABB and another AABB.
Definition: coal/BV/AABB.h:148
coal::AABB::axisOverlap
bool axisOverlap(const AABB &other, int axis_id) const
Check whether two AABB are overlapped along specific axis.
Definition: coal/BV/AABB.h:199
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::AABB::operator==
bool operator==(const AABB &other) const
Comparison operator.
Definition: coal/BV/AABB.h:91
coal::AABB::AABB
AABB(const Vec3s &v)
Creating an AABB at position v with zero size.
Definition: coal/BV/AABB.h:66
coal::AABB::AABB
AABB(const AABB &core, const Vec3s &delta)
Creating an AABB centered as core and is of half-dimension delta.
Definition: coal/BV/AABB.h:73
coal::AABB::AABB
AABB(const Vec3s &a, const Vec3s &b)
Creating an AABB with two endpoints a and b.
Definition: coal/BV/AABB.h:69
t
dictionary t
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::AABB::expand
AABB & expand(const Vec3s &delta)
expand the half size of the AABB by delta, and keep the center unchanged.
Definition: coal/BV/AABB.h:208
coal::AABB::size
CoalScalar size() const
Size of the AABB (used in BV_Splitter to order two AABBs)
Definition: coal/BV/AABB.h:161
obb.v
list v
Definition: obb.py:48


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