Represents an oriented bounding box.
More...
#include <obb.h>
Represents an oriented bounding box.
Definition at line 53 of file obb.h.
◆ OBB() [1/3]
Initialize an oriented bounding box at position 0, with 0 extents and identity orientation.
Definition at line 43 of file obb.cpp.
◆ OBB() [2/3]
bodies::OBB::OBB |
( |
const OBB & |
other | ) |
|
◆ OBB() [3/3]
bodies::OBB::OBB |
( |
const Eigen::Isometry3d & |
pose, |
|
|
const Eigen::Vector3d & |
extents |
|
) |
| |
◆ ~OBB()
◆ computeVertices()
Compute coordinates of the 8 vertices of this OBB.
- Returns
- The vertices.
Definition at line 169 of file obb.cpp.
◆ contains() [1/2]
bool bodies::OBB::contains |
( |
const Eigen::Vector3d & |
point | ) |
const |
Check if this OBB contains the given point.
- Parameters
-
- Returns
- Whether the point is inside or not.
Definition at line 159 of file obb.cpp.
◆ contains() [2/2]
bool bodies::OBB::contains |
( |
const OBB & |
obb | ) |
const |
Check if this OBB contains whole other OBB.
- Parameters
-
- Returns
- Whether the point is inside or not.
Definition at line 194 of file obb.cpp.
◆ extendApprox()
OBB * bodies::OBB::extendApprox |
( |
const OBB & |
box | ) |
|
Add the other OBB to this one and compute an approximate enclosing OBB.
- Parameters
-
- Returns
- Pointer to this OBB after the update.
Definition at line 138 of file obb.cpp.
◆ getExtents() [1/2]
Eigen::Vector3d bodies::OBB::getExtents |
( |
| ) |
const |
Get the extents of the OBB.
- Returns
- The extents.
Definition at line 99 of file obb.cpp.
◆ getExtents() [2/2]
void bodies::OBB::getExtents |
( |
Eigen::Vector3d & |
extents | ) |
const |
Get the extents of the OBB.
- Parameters
-
extents | [out] The extents. |
Definition at line 94 of file obb.cpp.
◆ getPose() [1/2]
Eigen::Isometry3d bodies::OBB::getPose |
( |
| ) |
const |
Get the pose of the OBB.
- Returns
- The pose.
Definition at line 119 of file obb.cpp.
◆ getPose() [2/2]
void bodies::OBB::getPose |
( |
Eigen::Isometry3d & |
pose | ) |
const |
Get The pose of the OBB.
- Parameters
-
Definition at line 106 of file obb.cpp.
◆ operator=()
OBB & bodies::OBB::operator= |
( |
const OBB & |
other | ) |
|
◆ overlaps()
bool bodies::OBB::overlaps |
( |
const OBB & |
other | ) |
const |
Check whether this and the given OBBs have nonempty intersection.
- Parameters
-
other | The other OBB to check. |
- Returns
- Whether the OBBs overlap.
Definition at line 164 of file obb.cpp.
◆ setPoseAndExtents()
void bodies::OBB::setPoseAndExtents |
( |
const Eigen::Isometry3d & |
pose, |
|
|
const Eigen::Vector3d & |
extents |
|
) |
| |
Set both the pose and extents of the OBB.
- Parameters
-
[in] | pose | New pose of the OBB. |
[in] | extents | New extents of the OBB. |
Definition at line 77 of file obb.cpp.
◆ toAABB() [1/2]
AABB bodies::OBB::toAABB |
( |
| ) |
const |
Convert this OBB to an axis-aligned BB.
- Returns
- The AABB.
Definition at line 126 of file obb.cpp.
◆ toAABB() [2/2]
void bodies::OBB::toAABB |
( |
AABB & |
aabb | ) |
const |
Convert this OBB to an axis-aligned BB.
- Parameters
-
Definition at line 133 of file obb.cpp.
◆ obb_
PIMPL pointer.
Definition at line 143 of file obb.h.
The documentation for this class was generated from the following files: