Go to the documentation of this file.
3 #include <fcl/config.h>
5 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
6 #include <fcl/BV/OBB.h>
17 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
21 Eigen::Map<Eigen::MatrixXd>(result.data.vs, 3, 1) = eigenVec;
28 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
31 return Eigen::Map<const Eigen::MatrixXd>(fclVec.data.vs, 3, 1);
47 #if FCL_MAJOR_VERSION > 0 || FCL_MINOR_VERSION > 5
49 obb_->extent.setZero();
51 obb_->axis.setIdentity();
54 obb_->axis[0][0] = 1.0;
55 obb_->axis[1][1] = 1.0;
56 obb_->axis[2][2] = 1.0;
65 OBB::OBB(
const Eigen::Isometry3d& pose,
const Eigen::Vector3d& extents)
79 const auto rotation = pose.linear();
81 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
86 obb_->axis = rotation;
108 pose = Eigen::Isometry3d::Identity();
110 #if FCL_MAJOR_VERSION == 0 && FCL_MINOR_VERSION == 5
115 pose.linear() =
obb_->axis;
121 Eigen::Isometry3d pose;
140 if (this->
getExtents() == Eigen::Vector3d::Zero())
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] },
186 for (
auto& v : result)
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.
Vector3< double > Vector3d
Represents an oriented bounding box.
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
fcl::OBB< double > FCL_OBB
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)
SaPCollisionManager< S >::SaPAABB * aabb
std::array< S, 6 > & extents()
bool overlaps(const OBB &other) const
Check whether this and the given OBBs have nonempty intersection.
Represents an axis-aligned bounding box.
geometric_shapes
Author(s): Ioan Sucan
, Gil Jones
autogenerated on Tue Aug 13 2024 02:40:57