obb.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, Open Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Open Robotics nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Martin Pecka */
36 
37 #ifndef GEOMETRIC_SHAPES_OBB_H
38 #define GEOMETRIC_SHAPES_OBB_H
39 
40 #include <memory>
41 
42 #include <Eigen/Core>
43 #include <Eigen/Geometry>
44 
46 #include <geometric_shapes/aabb.h>
47 
48 namespace bodies
49 {
50 class OBBPrivate;
51 
53 class OBB
54 {
55 public:
58  OBB();
59  OBB(const OBB& other);
60  OBB(const Eigen::Isometry3d& pose, const Eigen::Vector3d& extents);
61  virtual ~OBB();
62 
63  OBB& operator=(const OBB& other);
64 
70  void setPoseAndExtents(const Eigen::Isometry3d& pose, const Eigen::Vector3d& extents);
71 
76  Eigen::Vector3d getExtents() const;
77 
82  void getExtents(Eigen::Vector3d& extents) const;
83 
88  Eigen::Isometry3d getPose() const;
89 
94  void getPose(Eigen::Isometry3d& pose) const;
95 
100  AABB toAABB() const;
101 
106  void toAABB(AABB& aabb) const;
107 
113  OBB* extendApprox(const OBB& box);
114 
120  bool contains(const Eigen::Vector3d& point) const;
121 
127  bool overlaps(const OBB& other) const;
128 
134  bool contains(const OBB& obb) const;
135 
141 
142 protected:
144  std::unique_ptr<OBBPrivate> obb_;
145 };
146 } // namespace bodies
147 
148 #endif // GEOMETRIC_SHAPES_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()
bodies::OBB::OBB
OBB()
Initialize an oriented bounding box at position 0, with 0 extents and identity orientation.
Definition: obb.cpp:43
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
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
eigen_stl_containers.h
aabb.h
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
bodies
This set of classes allows quickly detecting whether a given point is inside an object or not....
Definition: aabb.h:42
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
bodies::OBB::overlaps
bool overlaps(const OBB &other) const
Check whether this and the given OBBs have nonempty intersection.
Definition: obb.cpp:164


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Sun Oct 1 2023 02:40:16