38 #ifndef HPP_FCL_GEOMETRIC_SHAPES_H 39 #define HPP_FCL_GEOMETRIC_SHAPES_H 41 #include <boost/math/constants/constants.hpp> 85 void computeLocalAABB();
114 if (other_ptr ==
nullptr)
return false;
117 return a == other.
a && b == other.
b && c == other.
c;
121 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
128 :
ShapeBase(), halfSide(x / 2, y / 2, z / 2) {}
135 if (
this == &other)
return *
this;
151 void computeLocalAABB();
160 Vec3f s(halfSide.cwiseAbs2() * V);
161 return (
Vec3f(s[1] + s[2], s[0] + s[2], s[0] + s[1]) / 3).asDiagonal();
173 if (value <= minInflationValue())
175 <<
"is two small. It should be at least: " 176 << minInflationValue(),
177 std::invalid_argument);
178 return std::make_pair(
Box(2 * (halfSide + Vec3f::Constant(value))),
184 const Box* other_ptr =
dynamic_cast<const Box*
>(&_other);
185 if (other_ptr ==
nullptr)
return false;
186 const Box& other = *other_ptr;
192 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
212 void computeLocalAABB();
218 FCL_REAL I = 0.4 * radius * radius * computeVolume();
219 return I * Matrix3f::Identity();
223 return 4 * boost::math::constants::pi<FCL_REAL>() * radius * radius *
236 if (value <= minInflationValue())
238 "value (" << value <<
") is two small. It should be at least: " 239 << minInflationValue(),
240 std::invalid_argument);
246 const Sphere* other_ptr =
dynamic_cast<const Sphere*
>(&_other);
247 if (other_ptr ==
nullptr)
return false;
248 const Sphere& other = *other_ptr;
250 return radius == other.
radius;
254 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
278 void computeLocalAABB();
285 FCL_REAL a2 = V * radii[0] * radii[0];
286 FCL_REAL b2 = V * radii[1] * radii[1];
288 return (
Matrix3f() << 0.2 * (b2 + c2), 0, 0, 0, 0.2 * (a2 + c2), 0, 0, 0,
294 return 4 * boost::math::constants::pi<FCL_REAL>() * radii[0] * radii[1] *
307 if (value <= minInflationValue())
309 "value (" << value <<
") is two small. It should be at least: " 310 << minInflationValue(),
311 std::invalid_argument);
312 return std::make_pair(
Ellipsoid(radii + Vec3f::Constant(value)),
319 if (other_ptr ==
nullptr)
return false;
322 return radii == other.
radii;
326 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
339 halfLength = lz_ / 2;
343 :
ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
355 void computeLocalAABB();
361 return boost::math::constants::pi<FCL_REAL>() * radius * radius *
362 ((halfLength * 2) + radius * 4 / 3.0);
366 FCL_REAL v_cyl = radius * radius * (halfLength * 2) *
367 boost::math::constants::pi<FCL_REAL>();
368 FCL_REAL v_sph = radius * radius * radius *
369 boost::math::constants::pi<FCL_REAL>() * 4 / 3.0;
371 FCL_REAL h2 = halfLength * halfLength;
373 FCL_REAL ix = v_cyl * (h2 / 3. + r2 / 4.) +
374 v_sph * (0.4 * r2 + h2 + 0.75 * radius * halfLength);
375 FCL_REAL iz = (0.5 * v_cyl + 0.4 * v_sph) * radius * radius;
377 return (
Matrix3f() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
389 if (value <= minInflationValue())
391 "value (" << value <<
") is two small. It should be at least: " 392 << minInflationValue(),
393 std::invalid_argument);
394 return std::make_pair(
Capsule(radius + value, 2 * halfLength),
401 if (other_ptr ==
nullptr)
return false;
402 const Capsule& other = *other_ptr;
408 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
420 halfLength = lz_ / 2;
424 :
ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
427 virtual Cone* clone()
const {
return new Cone(*
this); };
436 void computeLocalAABB();
442 return boost::math::constants::pi<FCL_REAL>() * radius * radius *
443 (halfLength * 2) / 3;
449 V * (0.4 * halfLength * halfLength + 3 * radius * radius / 20);
450 FCL_REAL iz = 0.3 * V * radius * radius;
452 return (
Matrix3f() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
466 if (value <= minInflationValue())
468 "value (" << value <<
") is two small. It should be at least: " 469 << minInflationValue(),
470 std::invalid_argument);
473 const FCL_REAL tan_alpha = 2 * halfLength / radius;
474 const FCL_REAL sin_alpha = tan_alpha / std::sqrt(1 + tan_alpha * tan_alpha);
475 const FCL_REAL top_inflation = value / sin_alpha;
476 const FCL_REAL bottom_inflation = value;
478 const FCL_REAL new_lz = 2 * halfLength + top_inflation + bottom_inflation;
479 const FCL_REAL new_cz = (top_inflation + bottom_inflation) / 2.;
480 const FCL_REAL new_radius = new_lz / tan_alpha;
482 return std::make_pair(
Cone(new_radius, new_lz),
488 const Cone* other_ptr =
dynamic_cast<const Cone*
>(&_other);
489 if (other_ptr ==
nullptr)
return false;
490 const Cone& other = *other_ptr;
496 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
507 halfLength = lz_ / 2;
511 :
ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
514 if (
this == &other)
return *
this;
516 this->radius = other.
radius;
531 void computeLocalAABB();
537 return boost::math::constants::pi<FCL_REAL>() * radius * radius *
543 FCL_REAL ix = V * (radius * radius / 4 + halfLength * halfLength / 3);
544 FCL_REAL iz = V * radius * radius / 2;
545 return (
Matrix3f() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
557 if (value <= minInflationValue())
559 "value (" << value <<
") is two small. It should be at least: " 560 << minInflationValue(),
561 std::invalid_argument);
562 return std::make_pair(
Cylinder(radius + value, 2 * (halfLength + value)),
569 if (other_ptr ==
nullptr)
return false;
576 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
595 static ConvexBase* convexHull(
const Vec3f* points,
unsigned int num_points,
597 const char* qhullCommand = NULL);
608 std::copy(points, points + num_points, copy.
points);
611 copy.ShapeBase::operator=(*this);
617 void computeLocalAABB();
630 unsigned char const&
count()
const {
return count_; }
641 if (count_ != other.
count_)
return false;
643 for (
int i = 0; i < count_; ++i) {
644 if (n_[i] != other.
n_[i])
return false;
670 own_storage_(false) {}
678 void initialize(
bool ownStorage,
Vec3f* points_,
unsigned int num_points_);
685 void set(
bool ownStorage,
Vec3f* points_,
unsigned int num_points_);
696 void computeCenter();
700 const ConvexBase* other_ptr =
dynamic_cast<const ConvexBase*
>(&_other);
701 if (other_ptr ==
nullptr)
return false;
702 const ConvexBase& other = *other_ptr;
704 if (num_points != other.
num_points)
return false;
706 for (
unsigned int i = 0; i < num_points; ++i) {
707 if (points[i] != other.
points[i])
return false;
710 for (
unsigned int i = 0; i < num_points; ++i) {
711 if (neighbors[i] != other.
neighbors[i])
return false;
714 return center == other.
center;
718 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
721 template <
typename PolygonT>
745 :
ShapeBase(other), n(other.n), d(other.d) {}
762 void computeLocalAABB();
768 return std::numeric_limits<FCL_REAL>::lowest();
778 if (value <= minInflationValue())
780 "value (" << value <<
") is two small. It should be at least: " 781 << minInflationValue(),
782 std::invalid_argument);
794 void unitNormalTest();
799 if (other_ptr ==
nullptr)
return false;
802 return n == other.
n && d == other.
d;
806 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
842 void computeLocalAABB();
855 void unitNormalTest();
859 const Plane* other_ptr =
dynamic_cast<const Plane*
>(&_other);
860 if (other_ptr ==
nullptr)
return false;
861 const Plane& other = *other_ptr;
863 return n == other.
n && d == other.
d;
867 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
ReturnMatrix copy(const Eigen::MatrixBase< Matrix > &mat)
std::pair< Capsule, Transform3f > inflated(const FCL_REAL value) const
Inflate the capsule by an amount given by value.
Vec3f halfSide
box side half-length
NODE_TYPE getNodeType() const
Get node type: a box.
NODE_TYPE getNodeType() const
Get node type: a cone.
Halfspace & operator=(const Halfspace &other)
operator =
virtual TriangleP * clone() const
Clone *this into a new TriangleP.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
std::pair< Sphere, Transform3f > inflated(const FCL_REAL value) const
Inflate the sphere by an amount given by value.
unsigned int const & operator[](int i) const
FCL_REAL minInflationValue() const
Ellipsoid centered at point zero.
Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
Vec3f computeCOM() const
compute center of mass
FCL_REAL halfLength
Half Length along z axis.
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Cylinder along Z axis. The cylinder is defined at its centroid.
FCL_REAL signedDistance(const Vec3f &p) const
Ellipsoid()
Default constructor.
Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
Halfspace(const Vec3f &n_, FCL_REAL d_)
Construct a half space with normal direction and offset.
TriangleP(const TriangleP &other)
Capsule(const Capsule &other)
Plane(const Plane &other)
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
bool initialize(MeshCollisionTraversalNode< BV, RelativeTransformationIsIdentity > &node, BVHModel< BV > &model1, Transform3f &tf1, BVHModel< BV > &model2, Transform3f &tf2, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
Initialize traversal node for collision between two meshes, given the current transforms.
FCL_REAL minInflationValue() const
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
NODE_TYPE getNodeType() const
Get node type: a capsule.
Half Space: this is equivalent to the Plane in ODE. The separation plane is defined as n * x = d; Poi...
Cone()
Default constructor.
bool operator!=(const Neighbors &other) const
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Box & operator=(const Box &other)
virtual ConvexBase * clone() const
.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
Capsule()
Default constructor.
Cylinder & operator=(const Cylinder &other)
FCL_REAL computeVolume() const
compute the volume
ConvexBase()
Construct an uninitialized convex object Initialization is done with ConvexBase::initialize.
Sphere()
Default constructor.
FCL_REAL computeVolume() const
compute the volume
Ellipsoid(FCL_REAL rx, FCL_REAL ry, FCL_REAL rz)
Box()
Default constructor.
Cylinder()
Default constructor.
Base class for all basic geometric shapes.
Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
Halfspace(FCL_REAL a, FCL_REAL b, FCL_REAL c, FCL_REAL d_)
Construct a plane with normal direction and offset.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
virtual Box * clone() const
Clone *this into a new Box.
TriangleP(const Vec3f &a_, const Vec3f &b_, const Vec3f &c_)
FCL_REAL radius
Radius of the cone.
FCL_REAL distance(const Vec3f &p) const
Halfspace(const Halfspace &other)
std::pair< Halfspace, Transform3f > inflated(const FCL_REAL value) const
Inflate the cylinder by an amount given by value.
bool operator==(const Neighbors &other) const
Center at zero point, axis aligned box.
Plane(const Vec3f &n_, FCL_REAL d_)
Construct a plane with normal direction and offset.
Plane & operator=(const Plane &other)
operator =
Ellipsoid(const Ellipsoid &other)
NODE_TYPE getNodeType() const
Get node type: a plane.
Cone(FCL_REAL radius_, FCL_REAL lz_)
Triangle stores the points instead of only indices of points.
virtual Halfspace * clone() const
Clone *this into a new Halfspace.
FCL_REAL computeVolume() const
compute the volume
std::pair< Cone, Transform3f > inflated(const FCL_REAL value) const
Inflate the cone by an amount given by value.
virtual Plane * clone() const
Clone *this into a new Plane.
Cone The base of the cone is at and the top is at .
Plane(FCL_REAL a, FCL_REAL b, FCL_REAL c, FCL_REAL d_)
Construct a plane with normal direction and offset.
FCL_REAL minInflationValue() const
unsigned int & operator[](int i)
FCL_REAL minInflationValue() const
FCL_REAL radius
Radius of the sphere.
Ellipsoid(const Vec3f &radii)
FCL_REAL radius
Radius of the cylinder.
Center at zero point sphere.
FCL_REAL computeVolume() const
compute the volume
NODE_TYPE getNodeType() const
Get node type: an ellipsoid.
FCL_REAL computeVolume() const
compute the volume
Capsule It is where is the distance between the point x and the capsule segment AB...
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, triangle), and octree
Base for convex polytope.
FCL_REAL computeVolume() const
compute the volume
unsigned char const & count() const
FCL_REAL minInflationValue() const
Sphere(const Sphere &other)
Cylinder(FCL_REAL radius_, FCL_REAL lz_)
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
NODE_TYPE getNodeType() const
Get node type: a conex polytope.
Capsule(FCL_REAL radius_, FCL_REAL lz_)
FCL_REAL signedDistance(const Vec3f &p) const
std::pair< Cylinder, Transform3f > inflated(const FCL_REAL value) const
Inflate the cylinder by an amount given by value.
FCL_REAL halfLength
Half Length along z axis.
Cylinder(const Cylinder &other)
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Vec3f radii
Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2.
std::pair< Ellipsoid, Transform3f > inflated(const FCL_REAL value) const
Inflate the ellipsoid by an amount given by value.
NODE_TYPE getNodeType() const
get the node type
The geometry for the object for collision or distance computation.
ShapeBase(const ShapeBase &other)
.
NODE_TYPE getNodeType() const
Get node type: a half space.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
FCL_REAL minInflationValue() const
Vec3f center
center of the convex polytope, this is used for collision: center is guaranteed in the internal of th...
FCL_REAL radius
Radius of capsule.
unsigned int * nneighbors_
FCL_REAL halfLength
Half Length along z axis.
OBJECT_TYPE getObjectType() const
Get object type: a geometric shape.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
FCL_REAL distance(const Vec3f &p) const
#define HPP_FCL_THROW_PRETTY(message, exception)
Matrix3f computeMomentofInertia() const
compute the inertia matrix, related to the origin
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
std::pair< Box, Transform3f > inflated(const FCL_REAL value) const
Inflate the box by an amount given by value.
NODE_TYPE getNodeType() const
Get node type: a sphere.
Vec3f * points
An array of the points of the polygon.
FCL_REAL minInflationValue() const
NODE_TYPE getNodeType() const
Get node type: a cylinder.
Box(FCL_REAL x, FCL_REAL y, FCL_REAL z)