37 #ifndef GEOMETRIC_SHAPES_OBB_H 38 #define GEOMETRIC_SHAPES_OBB_H 43 #include <Eigen/Geometry> 59 OBB(
const Eigen::Isometry3d& pose,
const Eigen::Vector3d& extents);
69 void setPoseAndExtents(
const Eigen::Isometry3d& pose,
const Eigen::Vector3d& extents);
81 void getExtents(Eigen::Vector3d& extents)
const;
87 Eigen::Isometry3d
getPose()
const;
93 void getPose(Eigen::Isometry3d& pose)
const;
119 bool contains(
const Eigen::Vector3d& point)
const;
143 std::unique_ptr<OBBPrivate>
obb_;
147 #endif // GEOMETRIC_SHAPES_OBB_H Eigen::Vector3d getExtents() const
Get the extents of the OBB.
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
std::unique_ptr< OBBPrivate > obb_
PIMPL pointer.
bool overlaps(const OBB &other) const
Check whether this and the given OBBs have nonempty intersection.
EigenSTL::vector_Vector3d computeVertices() const
Compute coordinates of the 8 vertices of this OBB.
Represents an oriented bounding box.
OBB * extendApprox(const OBB &box)
Add the other OBB to this one and compute an approximate enclosing OBB.
void setPoseAndExtents(const Eigen::Isometry3d &pose, const Eigen::Vector3d &extents)
Set both the pose and extents of the OBB.
bool contains(const Eigen::Vector3d &point) const
Check if this OBB contains the given point.
Eigen::Isometry3d getPose() const
Get the pose of the OBB.
AABB toAABB() const
Convert this OBB to an axis-aligned BB.
OBB & operator=(const OBB &other)
Represents an axis-aligned bounding box.
This set of classes allows quickly detecting whether a given point is inside an object or not...