Go to the documentation of this file.
38 #ifndef COAL_GEOMETRIC_SHAPES_H
39 #define COAL_GEOMETRIC_SHAPES_H
44 #include <boost/math/constants/constants.hpp>
65 m_swept_sphere_radius(other.m_swept_sphere_radius) {}
79 std::invalid_argument);
81 this->m_swept_sphere_radius = radius;
87 return this->m_swept_sphere_radius;
124 void computeLocalAABB();
154 if (other_ptr ==
nullptr)
return false;
157 return a == other.
a &&
b == other.
b &&
c == other.
c &&
162 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
176 if (
this == &other)
return *
this;
192 void computeLocalAABB();
201 Vec3s s(halfSide.cwiseAbs2() *
V);
202 return (
Vec3s(s[1] + s[2], s[0] + s[2], s[0] + s[1]) / 3).asDiagonal();
216 if (
value <= minInflationValue())
218 <<
"is two small. It should be at least: "
219 << minInflationValue(),
220 std::invalid_argument);
221 return std::make_pair(
Box(2 * (halfSide + Vec3s::Constant(
value))),
227 const Box* other_ptr =
dynamic_cast<const Box*
>(&_other);
228 if (other_ptr ==
nullptr)
return false;
229 const Box& other = *other_ptr;
231 return halfSide == other.
halfSide &&
236 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
256 void computeLocalAABB();
262 CoalScalar I = 0.4 * radius * radius * computeVolume();
263 return I * Matrix3s::Identity();
267 return 4 * boost::math::constants::pi<CoalScalar>() * radius * radius *
282 if (
value <= minInflationValue())
284 <<
") is two small. It should be at least: "
285 << minInflationValue(),
286 std::invalid_argument);
292 const Sphere* other_ptr =
dynamic_cast<const Sphere*
>(&_other);
293 if (other_ptr ==
nullptr)
return false;
294 const Sphere& other = *other_ptr;
296 return radius == other.
radius &&
301 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
325 void computeLocalAABB();
335 return (
Matrix3s() << 0.2 * (b2 +
c2), 0, 0, 0, 0.2 * (a2 +
c2), 0, 0, 0,
341 return 4 * boost::math::constants::pi<CoalScalar>() * radii[0] * radii[1] *
356 if (
value <= minInflationValue())
358 <<
") is two small. It should be at least: "
359 << minInflationValue(),
360 std::invalid_argument);
368 if (other_ptr ==
nullptr)
return false;
371 return radii == other.
radii &&
376 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
389 halfLength = lz_ / 2;
393 :
ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
405 void computeLocalAABB();
411 return boost::math::constants::pi<CoalScalar>() * radius * radius *
412 ((halfLength * 2) + radius * 4 / 3.0);
416 CoalScalar v_cyl = radius * radius * (halfLength * 2) *
417 boost::math::constants::pi<CoalScalar>();
419 boost::math::constants::pi<CoalScalar>() * 4 / 3.0;
424 v_sph * (0.4 *
r2 + h2 + 0.75 * radius * halfLength);
425 CoalScalar iz = (0.5 * v_cyl + 0.4 * v_sph) * radius * radius;
427 return (
Matrix3s() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
441 if (
value <= minInflationValue())
443 <<
") is two small. It should be at least: "
444 << minInflationValue(),
445 std::invalid_argument);
446 return std::make_pair(
Capsule(radius +
value, 2 * halfLength),
453 if (other_ptr ==
nullptr)
return false;
454 const Capsule& other = *other_ptr;
461 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
473 halfLength = lz_ / 2;
477 :
ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
480 virtual Cone* clone()
const {
return new Cone(*
this); };
489 void computeLocalAABB();
495 return boost::math::constants::pi<CoalScalar>() * radius * radius *
496 (halfLength * 2) / 3;
502 V * (0.4 * halfLength * halfLength + 3 * radius * radius / 20);
505 return (
Matrix3s() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
511 return -(std::min)(radius, halfLength);
523 if (
value <= minInflationValue())
525 <<
") is two small. It should be at least: "
526 << minInflationValue(),
527 std::invalid_argument);
530 const CoalScalar tan_alpha = 2 * halfLength / radius;
532 tan_alpha / std::sqrt(1 + tan_alpha * tan_alpha);
536 const CoalScalar new_lz = 2 * halfLength + top_inflation + bottom_inflation;
537 const CoalScalar new_cz = (top_inflation + bottom_inflation) / 2.;
538 const CoalScalar new_radius = new_lz / tan_alpha;
540 return std::make_pair(
Cone(new_radius, new_lz),
546 const Cone* other_ptr =
dynamic_cast<const Cone*
>(&_other);
547 if (other_ptr ==
nullptr)
return false;
548 const Cone& other = *other_ptr;
555 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
566 halfLength = lz_ / 2;
570 :
ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
573 if (
this == &other)
return *
this;
575 this->radius = other.
radius;
590 void computeLocalAABB();
596 return boost::math::constants::pi<CoalScalar>() * radius * radius *
602 CoalScalar ix =
V * (radius * radius / 4 + halfLength * halfLength / 3);
604 return (
Matrix3s() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
608 return -(std::min)(radius, halfLength);
620 if (
value <= minInflationValue())
622 <<
") is two small. It should be at least: "
623 << minInflationValue(),
624 std::invalid_argument);
632 if (other_ptr ==
nullptr)
return false;
640 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
659 static ConvexBase* convexHull(std::shared_ptr<std::vector<Vec3s>>& points,
660 unsigned int num_points,
bool keepTriangles,
661 const char* qhullCommand = NULL);
664 COAL_DEPRECATED
static ConvexBase* convexHull(
665 const Vec3s* points,
unsigned int num_points,
bool keepTriangles,
666 const char* qhullCommand = NULL);
676 void computeLocalAABB();
681 #ifdef COAL_HAS_QHULL
682 void buildDoubleDescription();
691 unsigned char const&
count()
const {
return count_; }
702 if (count_ != other.
count_)
return false;
704 for (
int i = 0; i < count_; ++i) {
705 if (n_[i] != other.
n_[i])
return false;
716 static constexpr
size_t num_vertices_large_convex_threshold = 32;
719 std::shared_ptr<std::vector<Vec3s>>
points;
754 static constexpr
size_t num_support_warm_starts = 14;
765 num_normals_and_offsets(0),
766 center(
Vec3s::Zero()) {}
774 void initialize(std::shared_ptr<std::vector<Vec3s>> points_,
775 unsigned int num_points_);
782 void set(std::shared_ptr<std::vector<Vec3s>> points_,
783 unsigned int num_points_);
789 #ifdef COAL_HAS_QHULL
794 void buildSupportWarmStart();
804 void computeCenter();
808 if (other_ptr ==
nullptr)
return false;
811 if (num_points != other.
num_points)
return false;
813 if ((!(points.get()) && other.
points.get()) ||
814 (points.get() && !(other.
points.get())))
816 if (points.get() && other.
points.get()) {
817 const std::vector<Vec3s>& points_ = *points;
818 const std::vector<Vec3s>& other_points_ = *(other.
points);
819 for (
unsigned int i = 0; i < num_points; ++i) {
820 if (points_[i] != (other_points_)[i])
return false;
824 if ((!(neighbors.get()) && other.
neighbors.get()) ||
825 (neighbors.get() && !(other.
neighbors.get())))
827 if (neighbors.get() && other.
neighbors.get()) {
828 const std::vector<Neighbors>& neighbors_ = *neighbors;
829 const std::vector<Neighbors>& other_neighbors_ = *(other.
neighbors);
830 for (
unsigned int i = 0; i < num_points; ++i) {
831 if (neighbors_[i] != other_neighbors_[i])
return false;
835 if ((!(normals.get()) && other.
normals.get()) ||
836 (normals.get() && !(other.
normals.get())))
838 if (normals.get() && other.
normals.get()) {
839 const std::vector<Vec3s>& normals_ = *normals;
840 const std::vector<Vec3s>& other_normals_ = *(other.
normals);
841 for (
unsigned int i = 0; i < num_normals_and_offsets; ++i) {
842 if (normals_[i] != other_normals_[i])
return false;
846 if ((!(offsets.get()) && other.
offsets.get()) ||
847 (offsets.get() && !(other.
offsets.get())))
849 if (offsets.get() && other.
offsets.get()) {
850 const std::vector<double>& offsets_ = *offsets;
851 const std::vector<double>& other_offsets_ = *(other.
offsets);
852 for (
unsigned int i = 0; i < num_normals_and_offsets; ++i) {
853 if (offsets_[i] != other_offsets_[i])
return false;
857 if (this->support_warm_starts.
points.size() !=
859 this->support_warm_starts.
indices.size() !=
864 for (
size_t i = 0; i < this->support_warm_starts.
points.size(); ++i) {
865 if (this->support_warm_starts.
points[i] !=
867 this->support_warm_starts.indices[i] !=
873 return center == other.
center &&
878 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
881 template <
typename PolygonT>
921 return n.dot(p) - (
d + this->getSweptSphereRadius());
925 return std::abs(this->signedDistance(p));
929 void computeLocalAABB();
935 return std::numeric_limits<CoalScalar>::lowest();
947 if (
value <= minInflationValue())
949 <<
") is two small. It should be at least: "
950 << minInflationValue(),
951 std::invalid_argument);
963 void unitNormalTest();
968 if (other_ptr ==
nullptr)
return false;
971 return n == other.
n &&
d == other.
d &&
976 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1013 std::abs(n.dot(p) -
d) - this->getSweptSphereRadius();
1017 if (signed_dist >= 0) {
1018 return -signed_dist;
1024 return std::abs(std::abs(n.dot(p) -
d) - this->getSweptSphereRadius());
1028 void computeLocalAABB();
1041 void unitNormalTest();
1045 const Plane* other_ptr =
dynamic_cast<const Plane*
>(&_other);
1046 if (other_ptr ==
nullptr)
return false;
1047 const Plane& other = *other_ptr;
1049 return n == other.
n &&
d == other.
d &&
1054 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
NODE_TYPE getNodeType() const
Get node type: a box.
std::pair< Cone, Transform3s > inflated(const CoalScalar value) const
Inflate the cone by an amount given by value. This value can be positive or negative but must always ...
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
std::pair< Cylinder, Transform3s > inflated(const CoalScalar value) const
Inflate the cylinder by an amount given by value. This value can be positive or negative but must alw...
Ellipsoid(const Ellipsoid &other)
NODE_TYPE getNodeType() const
Get node type: a cylinder.
std::pair< Halfspace, Transform3s > inflated(const CoalScalar value) const
Inflate the halfspace by an amount given by value. This value can be positive or negative but must al...
std::pair< Sphere, Transform3s > inflated(const CoalScalar value) const
Inflate the sphere by an amount given by value. This value can be positive or negative but must alway...
CoalScalar halfLength
Half Length along z axis.
virtual TriangleP * clone() const
Clone *this into a new TriangleP.
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
CoalScalar minInflationValue() const
Box & operator=(const Box &other)
NODE_TYPE getNodeType() const
Get node type: a convex polytope.
CoalScalar computeVolume() const
compute the volume
virtual Box * clone() const
Clone *this into a new Box.
virtual ConvexBase * clone() const
Clone (deep copy). This method is consistent with BVHModel clone method. The copy constructor is call...
bool operator==(const Neighbors &other) const
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
std::shared_ptr< std::vector< Neighbors > > neighbors
Neighbors of each vertex. It is an array of size num_points. For each vertex, it contains the number ...
QhullRidge – Qhull's ridge structure, ridgeT, as a C++ class.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
unsigned int & operator[](int i)
Plane & operator=(const Plane &other)
operator =
Ellipsoid()
Default constructor.
Vec3s computeCOM() const
compute center of mass
Capsule(const Capsule &other)
Cylinder(CoalScalar radius_, CoalScalar lz_)
Ellipsoid(const Vec3s &radii)
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
CoalScalar halfLength
Half Length along z axis.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Capsule It is where is the distance between the point x and the capsule segment AB,...
CoalScalar radius
Radius of the cylinder.
ConvexBase()
Construct an uninitialized convex object Initialization is done with ConvexBase::initialize.
bool operator!=(const Neighbors &other) const
NODE_TYPE getNodeType() const
get the node type
OBJECT_TYPE getObjectType() const
Get object type: a geometric shape.
Cone(CoalScalar radius_, CoalScalar lz_)
Sphere(CoalScalar radius_)
CoalScalar computeVolume() const
compute the volume
Ellipsoid centered at point zero.
CoalScalar distance(const Vec3s &p) const
std::shared_ptr< std::vector< Vec3s > > normals
An array of the normals of the polygon.
NODE_TYPE getNodeType() const
Get node type: a cone.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
The geometry for the object for collision or distance computation.
Sphere()
Default constructor.
TriangleP(const TriangleP &other)
Vec3s radii
Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2.
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
CoalScalar minInflationValue() const
Center at zero point, axis aligned box.
NODE_TYPE getNodeType() const
Get node type: a capsule.
unsigned char const & count() const
Center at zero point sphere.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
CoalScalar minInflationValue() const
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Box(CoalScalar x, CoalScalar y, CoalScalar z)
CoalScalar minInflationValue() const
Interface to Qhull from C++.
virtual Halfspace * clone() const
Clone *this into a new Halfspace.
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
CoalScalar computeVolume() const
compute the volume
unsigned int num_normals_and_offsets
CoalScalar signedDistance(const Vec3s &p) const
CoalScalar distance(const Vec3s &p) const
CoalScalar computeVolume() const
compute the volume
The support warm start polytope contains certain points of this which are support points in specific ...
ShapeBase(const ShapeBase &other)
 
Capsule(CoalScalar radius_, CoalScalar lz_)
CoalScalar computeVolume() const
compute the volume
NODE_TYPE getNodeType() const
Get node type: a half space.
CoalScalar halfLength
Half Length along z axis.
Base class for all basic geometric shapes.
CoalScalar computeVolume() const
compute the volume
NODE_TYPE getNodeType() const
Get node type: an ellipsoid.
#define COAL_THROW_PRETTY(message, exception)
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
NODE_TYPE getNodeType() const
Get node type: a sphere.
CoalScalar signedDistance(const Vec3s &p) const
Ellipsoid(CoalScalar rx, CoalScalar ry, CoalScalar rz)
Cylinder along Z axis. The cylinder is defined at its centroid.
Plane(const Plane &other)
Plane(CoalScalar a, CoalScalar b, CoalScalar c, CoalScalar d_)
Construct a plane with normal direction and offset.
Cone()
Default constructor.
unsigned int const & operator[](int i) const
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
TriangleP(const Vec3s &a_, const Vec3s &b_, const Vec3s &c_)
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Triangle stores the points instead of only indices of points.
Halfspace & operator=(const Halfspace &other)
operator =
Vec3s center
center of the convex polytope, this is used for collision: center is guaranteed in the internal of th...
CoalScalar getSweptSphereRadius() const
Get radius of sphere swept around the shape. This radius is always >= 0.
Cone The base of the cone is at and the top is at .
virtual Plane * clone() const
Clone *this into a new Plane.
std::vector< Vec3s > points
Array of support points to warm start the support function computation.
Vec3s halfSide
box side half-length
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
CoalScalar radius
Radius of the sphere.
NODE_TYPE getNodeType() const
Get node type: a plane.
CoalScalar radius
Radius of the cone.
Capsule()
Default constructor.
std::shared_ptr< std::vector< double > > offsets
An array of the offsets to the normals of the polygon. Note: there are as many offsets as normals.
CoalScalar d
Plane offset.
Plane(const Vec3s &n_, CoalScalar d_)
Construct a plane with normal direction and offset.
void setSweptSphereRadius(CoalScalar radius)
Set radius of sphere swept around the shape. Must be >= 0.
CoalScalar radius
Radius of capsule.
Halfspace(const Halfspace &other)
Cylinder(const Cylinder &other)
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
std::vector< int > indices
Indices of the support points warm starts. These are the indices of the real convex,...
Sphere(const Sphere &other)
Halfspace(CoalScalar a, CoalScalar b, CoalScalar c, CoalScalar d_)
Construct a plane with normal direction and offset.
CoalScalar minInflationValue() const
Cylinder()
Default constructor.
CoalScalar minInflationValue() const
CoalScalar minInflationValue() const
std::shared_ptr< std::vector< unsigned int > > nneighbors_
Array of indices of the neighbors of each vertex. Since we don't know a priori the number of neighbor...
Halfspace(const Vec3s &n_, CoalScalar d_)
Construct a half space with normal direction and offset.
std::pair< Ellipsoid, Transform3s > inflated(const CoalScalar value) const
Inflate the ellipsoid by an amount given by value. This value can be positive or negative but must al...
SupportWarmStartPolytope support_warm_starts
Support warm start polytopes.
std::shared_ptr< std::vector< Vec3s > > points
An array of the points of the polygon.
Box()
Default constructor.
std::pair< Capsule, Transform3s > inflated(const CoalScalar value) const
Inflate the capsule by an amount given by value. This value can be positive or negative but must alwa...
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
CoalScalar d
Plane offset.
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
bool initialize(MeshCollisionTraversalNode< BV, RelativeTransformationIsIdentity > &node, BVHModel< BV > &model1, Transform3s &tf1, BVHModel< BV > &model2, Transform3s &tf2, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
Initialize traversal node for collision between two meshes, given the current transforms.
std::pair< Box, Transform3s > inflated(const CoalScalar value) const
Inflate the box by an amount given by value. This value can be positive or negative but must always >...
Cylinder & operator=(const Cylinder &other)
Base for convex polytope.
hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:58