Go to the documentation of this file.
37 #ifndef GEOMETRIC_SHAPES_OBB_H
38 #define GEOMETRIC_SHAPES_OBB_H
43 #include <Eigen/Geometry>
60 OBB(
const Eigen::Isometry3d& pose,
const Eigen::Vector3d& extents);
70 void setPoseAndExtents(
const Eigen::Isometry3d& pose,
const Eigen::Vector3d& extents);
82 void getExtents(Eigen::Vector3d& extents)
const;
88 Eigen::Isometry3d
getPose()
const;
94 void getPose(Eigen::Isometry3d& pose)
const;
106 void toAABB(AABB& aabb)
const;
144 std::unique_ptr<OBBPrivate>
obb_;
148 #endif // GEOMETRIC_SHAPES_OBB_H
Eigen::Vector3d getExtents() const
Get the extents of the OBB.
AABB toAABB() const
Convert this OBB to an axis-aligned BB.
OBB()
Initialize an oriented bounding box at position 0, with 0 extents and identity orientation.
OBB * extendApprox(const OBB &box)
Add the other OBB to this one and compute an approximate enclosing OBB.
std::unique_ptr< OBBPrivate > obb_
PIMPL pointer.
bool contains(const Eigen::Vector3d &point) const
Check if this OBB contains the given point.
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
std::chrono::system_clock::time_point point
Eigen::Isometry3d getPose() const
Get the pose of the OBB.
This set of classes allows quickly detecting whether a given point is inside an object or not....
EigenSTL::vector_Vector3d computeVertices() const
Compute coordinates of the 8 vertices of this OBB.
void setPoseAndExtents(const Eigen::Isometry3d &pose, const Eigen::Vector3d &extents)
Set both the pose and extents of the OBB.
OBB & operator=(const OBB &other)
bool overlaps(const OBB &other) const
Check whether this and the given OBBs have nonempty intersection.
geometric_shapes
Author(s): Ioan Sucan
, Gil Jones
autogenerated on Tue Aug 13 2024 02:40:57