obb.cpp
Go to the documentation of this file.
1 #include <geometric_shapes/obb.h>
2 
3 #include <fcl/config.h>
4 
5 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
6 #include <fcl/BV/OBB.h>
7 typedef fcl::Vec3f FCL_Vec3;
8 typedef fcl::OBB FCL_OBB;
9 #else
10 #include <fcl/math/bv/OBB.h>
13 #endif
14 
15 namespace bodies
16 {
17 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
18 inline FCL_Vec3 toFcl(const Eigen::Vector3d& eigenVec)
19 {
20  FCL_Vec3 result;
21  Eigen::Map<Eigen::MatrixXd>(result.data.vs, 3, 1) = eigenVec;
22  return result;
23 }
24 #else
25 #define toFcl
26 #endif
27 
28 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
29 Eigen::Vector3d fromFcl(const FCL_Vec3& fclVec)
30 {
31  return Eigen::Map<const Eigen::MatrixXd>(fclVec.data.vs, 3, 1);
32 }
33 #else
34 #define fromFcl
35 #endif
36 
37 class OBBPrivate : public FCL_OBB
38 {
39 public:
40  using FCL_OBB::OBB;
41 };
42 
44 {
45  obb_.reset(new OBBPrivate);
46  // Initialize the OBB to position 0, with 0 extents and identity rotation
47 #if FCL_MAJOR_VERSION > 0 || FCL_MINOR_VERSION > 5
48  // FCL 0.6+ does not zero-initialize the OBB.
49  obb_->extent.setZero();
50  obb_->To.setZero();
51  obb_->axis.setIdentity();
52 #else
53  // FCL 0.5 zero-initializes the OBB, so we just put the identity into orientation.
54  obb_->axis[0][0] = 1.0;
55  obb_->axis[1][1] = 1.0;
56  obb_->axis[2][2] = 1.0;
57 #endif
58 }
59 
60 OBB::OBB(const OBB& other)
61 {
62  obb_.reset(new OBBPrivate(*other.obb_));
63 }
64 
65 OBB::OBB(const Eigen::Isometry3d& pose, const Eigen::Vector3d& extents)
66 {
67  obb_.reset(new OBBPrivate);
69 }
70 
71 OBB& OBB::operator=(const OBB& other)
72 {
73  *obb_ = *other.obb_;
74  return *this;
75 }
76 
77 void OBB::setPoseAndExtents(const Eigen::Isometry3d& pose, const Eigen::Vector3d& extents)
78 {
79  const auto rotation = pose.linear();
80 
81 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
82  obb_->axis[0] = toFcl(rotation.col(0));
83  obb_->axis[1] = toFcl(rotation.col(1));
84  obb_->axis[2] = toFcl(rotation.col(2));
85 #else
86  obb_->axis = rotation;
87 #endif
88 
89  obb_->To = toFcl(pose.translation());
90 
91  obb_->extent = { extents[0] / 2.0, extents[1] / 2.0, extents[2] / 2.0 };
92 }
93 
94 void OBB::getExtents(Eigen::Vector3d& extents) const
95 {
96  extents = 2 * fromFcl(obb_->extent);
97 }
98 
99 Eigen::Vector3d OBB::getExtents() const
100 {
101  Eigen::Vector3d extents;
103  return extents;
104 }
105 
106 void OBB::getPose(Eigen::Isometry3d& pose) const
107 {
108  pose = Eigen::Isometry3d::Identity();
109  pose.translation() = fromFcl(obb_->To);
110 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
111  pose.linear().col(0) = fromFcl(obb_->axis[0]);
112  pose.linear().col(1) = fromFcl(obb_->axis[1]);
113  pose.linear().col(2) = fromFcl(obb_->axis[2]);
114 #else
115  pose.linear() = obb_->axis;
116 #endif
117 }
118 
119 Eigen::Isometry3d OBB::getPose() const
120 {
121  Eigen::Isometry3d pose;
122  getPose(pose);
123  return pose;
124 }
125 
127 {
128  AABB result;
129  toAABB(result);
130  return result;
131 }
132 
133 void OBB::toAABB(AABB& aabb) const
134 {
135  aabb.extendWithTransformedBox(getPose(), getExtents());
136 }
137 
139 {
140  if (this->getExtents() == Eigen::Vector3d::Zero())
141  {
142  *obb_ = *box.obb_;
143  return this;
144  }
145 
146  if (this->contains(box))
147  return this;
148 
149  if (box.contains(*this))
150  {
151  *obb_ = *box.obb_;
152  return this;
153  }
154 
155  *this->obb_ += *box.obb_;
156  return this;
157 }
158 
159 bool OBB::contains(const Eigen::Vector3d& point) const
160 {
161  return obb_->contain(toFcl(point));
162 }
163 
164 bool OBB::overlaps(const bodies::OBB& other) const
165 {
166  return obb_->overlap(*other.obb_);
167 }
168 
170 {
171  const Eigen::Vector3d e = getExtents() / 2; // do not use auto type, Eigen would be inefficient
172  // clang-format off
173  EigenSTL::vector_Vector3d result = {
174  { -e[0], -e[1], -e[2] },
175  { -e[0], -e[1], e[2] },
176  { -e[0], e[1], -e[2] },
177  { -e[0], e[1], e[2] },
178  { e[0], -e[1], -e[2] },
179  { e[0], -e[1], e[2] },
180  { e[0], e[1], -e[2] },
181  { e[0], e[1], e[2] },
182  };
183  // clang-format on
184 
185  const auto pose = getPose();
186  for (auto& v : result)
187  {
188  v = pose * v;
189  }
190 
191  return result;
192 }
193 
194 bool OBB::contains(const OBB& obb) const
195 {
196  for (const auto& v : obb.computeVertices())
197  {
198  if (!contains(v))
199  return false;
200  }
201  return true;
202 }
203 
204 OBB::~OBB() = default;
205 
206 } // namespace bodies
obb.h
bodies::OBB::getExtents
Eigen::Vector3d getExtents() const
Get the extents of the OBB.
Definition: obb.cpp:99
bodies::OBB::toAABB
AABB toAABB() const
Convert this OBB to an axis-aligned BB.
Definition: obb.cpp:126
bodies::OBB::~OBB
virtual ~OBB()
FCL_Vec3
fcl::Vector3d FCL_Vec3
Definition: obb.cpp:11
bodies::OBB::OBB
OBB()
Initialize an oriented bounding box at position 0, with 0 extents and identity orientation.
Definition: obb.cpp:43
fromFcl
#define fromFcl
Definition: obb.cpp:34
toFcl
#define toFcl
Definition: obb.cpp:25
bodies::OBB::extendApprox
OBB * extendApprox(const OBB &box)
Add the other OBB to this one and compute an approximate enclosing OBB.
Definition: obb.cpp:138
bodies::OBB::obb_
std::unique_ptr< OBBPrivate > obb_
PIMPL pointer.
Definition: obb.h:176
fcl::Vector3d
Vector3< double > Vector3d
fcl::OBB
bodies::OBB
Represents an oriented bounding box.
Definition: obb.h:85
bodies::OBB::contains
bool contains(const Eigen::Vector3d &point) const
Check if this OBB contains the given point.
Definition: obb.cpp:159
EigenSTL::vector_Vector3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
FCL_OBB
fcl::OBB< double > FCL_OBB
Definition: obb.cpp:12
point
std::chrono::system_clock::time_point point
bodies::OBB::getPose
Eigen::Isometry3d getPose() const
Get the pose of the OBB.
Definition: obb.cpp:119
OBB.h
bodies
This set of classes allows quickly detecting whether a given point is inside an object or not....
Definition: aabb.h:42
bodies::OBBPrivate
Definition: obb.cpp:37
bodies::OBB::computeVertices
EigenSTL::vector_Vector3d computeVertices() const
Compute coordinates of the 8 vertices of this OBB.
Definition: obb.cpp:169
bodies::OBB::setPoseAndExtents
void setPoseAndExtents(const Eigen::Isometry3d &pose, const Eigen::Vector3d &extents)
Set both the pose and extents of the OBB.
Definition: obb.cpp:77
bodies::OBB::operator=
OBB & operator=(const OBB &other)
Definition: obb.cpp:71
aabb
SaPCollisionManager< S >::SaPAABB * aabb
extents
std::array< S, 6 > & extents()
fcl::OBB::OBB
OBB()
bodies::OBB::overlaps
bool overlaps(const OBB &other) const
Check whether this and the given OBBs have nonempty intersection.
Definition: obb.cpp:164
bodies::AABB
Represents an axis-aligned bounding box.
Definition: aabb.h:77


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Tue Aug 13 2024 02:40:57