Go to the documentation of this file.
   47   std::vector<Vec3s> result(8);
 
   66   std::vector<Vec3s> result(12);
 
   91   std::vector<Vec3s> result(12);
 
  125   std::vector<Vec3s> result(36);
 
  180   std::vector<Vec3s> result(7);
 
  201   std::vector<Vec3s> result(12);
 
  228   const std::vector<Vec3s>& points_ = *(convex.
points);
 
  229   for (std::size_t i = 0; i < convex.
num_points; ++i) {
 
  238   std::vector<Vec3s> result(3);
 
  286   result[1].setSweptSphereRadius(
a.getSweptSphereRadius());
 
  297   bv.
max_ = T + v_delta;
 
  298   bv.
min_ = T - v_delta;
 
  306   bv.
max_ = T + v_delta;
 
  307   bv.
min_ = T - v_delta;
 
  317   bv.
max_ = T + v_delta;
 
  318   bv.
min_ = T - v_delta;
 
  328   bv.
max_ = T + v_delta;
 
  329   bv.
min_ = T - v_delta;
 
  344   Vec3s v_delta(x_range, y_range, z_range);
 
  345   bv.
max_ = T + v_delta;
 
  346   bv.
min_ = T - v_delta;
 
  362   Vec3s v_delta(x_range, y_range, z_range);
 
  363   bv.
max_ = T + v_delta;
 
  364   bv.
min_ = T - v_delta;
 
  374   const std::vector<Vec3s>& points_ = *(s.
points);
 
  375   for (std::size_t i = 0; i < s.
num_points; ++i) {
 
  376     Vec3s new_p = 
R * points_[i] + T;
 
  397   bv_.
min_ = Vec3s::Constant(-(std::numeric_limits<CoalScalar>::max)());
 
  398   bv_.
max_ = Vec3s::Constant((std::numeric_limits<CoalScalar>::max)());
 
  429   bv_.
min_ = Vec3s::Constant(-(std::numeric_limits<CoalScalar>::max)());
 
  430   bv_.
max_ = Vec3s::Constant((std::numeric_limits<CoalScalar>::max)());
 
  435     } 
else if (n[0] > 0) {
 
  442     } 
else if (n[1] > 0) {
 
  449     } 
else if (n[2] > 0) {
 
  480   bv.
axes.setIdentity();
 
  494   bv.
axes.noalias() = 
R;
 
  508   bv.
axes.noalias() = 
R;
 
  523   bv.
axes.noalias() = 
R;
 
  539   bv.
axes.applyOnTheLeft(
R);
 
  541   bv.
To = 
R * bv.
To + T;
 
  552   bv.
axes.setIdentity();
 
  554   bv.
extent.setConstant(((std::numeric_limits<CoalScalar>::max)()));
 
  565   bv.
axes.setIdentity();
 
  568       (std::numeric_limits<CoalScalar>::max)();
 
  592   bv.
spheres[0].
r = (std::numeric_limits<CoalScalar>::max)();
 
  598   if (s.getSweptSphereRadius() > 0) {
 
  607   for (
short i = 0; i < 
D; ++i)
 
  608     bv.dist(i) = -(std::numeric_limits<CoalScalar>::max)();
 
  609   for (
short i = 
D; i < 2 * 
D; ++i)
 
  610     bv.dist(i) = (std::numeric_limits<CoalScalar>::max)();
 
  627   } 
else if (n[2] == (
CoalScalar)0.0 && n[0] == n[1]) {
 
  629       bv.dist(
D + 3) = n[0] * 
d * 2;
 
  631       bv.dist(3) = n[0] * 
d * 2;
 
  632   } 
else if (n[1] == (
CoalScalar)0.0 && n[0] == n[2]) {
 
  634       bv.dist(
D + 4) = n[0] * 
d * 2;
 
  636       bv.dist(4) = n[0] * 
d * 2;
 
  637   } 
else if (n[0] == (
CoalScalar)0.0 && n[1] == n[2]) {
 
  639       bv.dist(
D + 5) = n[1] * 
d * 2;
 
  641       bv.dist(5) = n[1] * 
d * 2;
 
  644       bv.dist(
D + 6) = n[0] * 
d * 2;
 
  646       bv.dist(6) = n[0] * 
d * 2;
 
  649       bv.dist(
D + 7) = n[0] * 
d * 2;
 
  651       bv.dist(7) = n[0] * 
d * 2;
 
  658   if (s.getSweptSphereRadius() > 0) {
 
  668   for (
short i = 0; i < 
D; ++i)
 
  669     bv.dist(i) = -(std::numeric_limits<CoalScalar>::max)();
 
  670   for (
short i = 
D; i < 2 * 
D; ++i)
 
  671     bv.dist(i) = (std::numeric_limits<CoalScalar>::max)();
 
  688   } 
else if (n[2] == (
CoalScalar)0.0 && n[0] == n[1]) {
 
  690       bv.dist(
D + 3) = n[0] * 
d * 2;
 
  692       bv.dist(3) = n[0] * 
d * 2;
 
  693   } 
else if (n[1] == (
CoalScalar)0.0 && n[0] == n[2]) {
 
  695       bv.dist(
D + 4) = n[0] * 
d * 2;
 
  697       bv.dist(4) = n[0] * 
d * 2;
 
  698   } 
else if (n[0] == (
CoalScalar)0.0 && n[1] == n[2]) {
 
  700       bv.dist(
D + 5) = n[1] * 
d * 2;
 
  702       bv.dist(5) = n[1] * 
d * 2;
 
  705       bv.dist(
D + 6) = n[0] * 
d * 2;
 
  707       bv.dist(6) = n[0] * 
d * 2;
 
  710       bv.dist(
D + 7) = n[0] * 
d * 2;
 
  712       bv.dist(7) = n[0] * 
d * 2;
 
  715       bv.dist(
D + 8) = n[1] * 
d * 2;
 
  717       bv.dist(8) = n[1] * 
d * 2;
 
  724   if (s.getSweptSphereRadius() > 0) {
 
  734   for (
short i = 0; i < 
D; ++i)
 
  735     bv.dist(i) = -(std::numeric_limits<CoalScalar>::max)();
 
  736   for (
short i = 
D; i < 2 * 
D; ++i)
 
  737     bv.dist(i) = (std::numeric_limits<CoalScalar>::max)();
 
  754   } 
else if (n[2] == (
CoalScalar)0.0 && n[0] == n[1]) {
 
  756       bv.dist(
D + 3) = n[0] * 
d * 2;
 
  758       bv.dist(3) = n[0] * 
d * 2;
 
  759   } 
else if (n[1] == (
CoalScalar)0.0 && n[0] == n[2]) {
 
  761       bv.dist(
D + 4) = n[0] * 
d * 2;
 
  763       bv.dist(4) = n[0] * 
d * 2;
 
  764   } 
else if (n[0] == (
CoalScalar)0.0 && n[1] == n[2]) {
 
  766       bv.dist(
D + 5) = n[1] * 
d * 2;
 
  768       bv.dist(5) = n[1] * 
d * 2;
 
  771       bv.dist(
D + 6) = n[0] * 
d * 2;
 
  773       bv.dist(6) = n[0] * 
d * 2;
 
  776       bv.dist(
D + 7) = n[0] * 
d * 2;
 
  778       bv.dist(7) = n[0] * 
d * 2;
 
  781       bv.dist(
D + 8) = n[1] * 
d * 2;
 
  783       bv.dist(8) = n[1] * 
d * 2;
 
  786       bv.dist(
D + 9) = n[0] * 
d * 3;
 
  788       bv.dist(9) = n[0] * 
d * 3;
 
  791       bv.dist(
D + 10) = n[0] * 
d * 3;
 
  793       bv.dist(10) = n[0] * 
d * 3;
 
  796       bv.dist(
D + 11) = n[1] * 
d * 3;
 
  798       bv.dist(11) = n[1] * 
d * 3;
 
  810   bv.
axes.col(0).noalias() = n;
 
  812   bv.
extent << 0, (std::numeric_limits<CoalScalar>::max)(),
 
  813       (std::numeric_limits<CoalScalar>::max)();
 
  829   bv.
axes.col(0).noalias() = n;
 
  831   bv.
length[0] = (std::numeric_limits<CoalScalar>::max)();
 
  832   bv.
length[1] = (std::numeric_limits<CoalScalar>::max)();
 
  860   bv.
spheres[0].
r = (std::numeric_limits<CoalScalar>::max)();
 
  866   if (s.getSweptSphereRadius() > 0) {
 
  876   for (
short i = 0; i < 
D; ++i)
 
  877     bv.dist(i) = -(std::numeric_limits<CoalScalar>::max)();
 
  878   for (
short i = 
D; i < 2 * 
D; ++i)
 
  879     bv.dist(i) = (std::numeric_limits<CoalScalar>::max)();
 
  883       bv.dist(0) = bv.dist(
D) = 
d;
 
  885       bv.dist(0) = bv.dist(
D) = -
d;
 
  888       bv.dist(1) = bv.dist(
D + 1) = 
d;
 
  890       bv.dist(1) = bv.dist(
D + 1) = -
d;
 
  893       bv.dist(2) = bv.dist(
D + 2) = 
d;
 
  895       bv.dist(2) = bv.dist(
D + 2) = -
d;
 
  896   } 
else if (n[2] == (
CoalScalar)0.0 && n[0] == n[1]) {
 
  897     bv.dist(3) = bv.dist(
D + 3) = n[0] * 
d * 2;
 
  898   } 
else if (n[1] == (
CoalScalar)0.0 && n[0] == n[2]) {
 
  899     bv.dist(4) = bv.dist(
D + 4) = n[0] * 
d * 2;
 
  900   } 
else if (n[0] == (
CoalScalar)0.0 && n[1] == n[2]) {
 
  901     bv.dist(6) = bv.dist(
D + 5) = n[1] * 
d * 2;
 
  903     bv.dist(6) = bv.dist(
D + 6) = n[0] * 
d * 2;
 
  905     bv.dist(7) = bv.dist(
D + 7) = n[0] * 
d * 2;
 
  912   if (s.getSweptSphereRadius() > 0) {
 
  922   for (
short i = 0; i < 
D; ++i)
 
  923     bv.dist(i) = -(std::numeric_limits<CoalScalar>::max)();
 
  924   for (
short i = 
D; i < 2 * 
D; ++i)
 
  925     bv.dist(i) = (std::numeric_limits<CoalScalar>::max)();
 
  929       bv.dist(0) = bv.dist(
D) = 
d;
 
  931       bv.dist(0) = bv.dist(
D) = -
d;
 
  934       bv.dist(1) = bv.dist(
D + 1) = 
d;
 
  936       bv.dist(1) = bv.dist(
D + 1) = -
d;
 
  939       bv.dist(2) = bv.dist(
D + 2) = 
d;
 
  941       bv.dist(2) = bv.dist(
D + 2) = -
d;
 
  942   } 
else if (n[2] == (
CoalScalar)0.0 && n[0] == n[1]) {
 
  943     bv.dist(3) = bv.dist(
D + 3) = n[0] * 
d * 2;
 
  944   } 
else if (n[1] == (
CoalScalar)0.0 && n[0] == n[2]) {
 
  945     bv.dist(4) = bv.dist(
D + 4) = n[0] * 
d * 2;
 
  946   } 
else if (n[0] == (
CoalScalar)0.0 && n[1] == n[2]) {
 
  947     bv.dist(5) = bv.dist(
D + 5) = n[1] * 
d * 2;
 
  949     bv.dist(6) = bv.dist(
D + 6) = n[0] * 
d * 2;
 
  951     bv.dist(7) = bv.dist(
D + 7) = n[0] * 
d * 2;
 
  953     bv.dist(8) = bv.dist(
D + 8) = n[1] * 
d * 2;
 
  960   if (s.getSweptSphereRadius() > 0) {
 
  970   for (
short i = 0; i < 
D; ++i)
 
  971     bv.dist(i) = -(std::numeric_limits<CoalScalar>::max)();
 
  972   for (
short i = 
D; i < 2 * 
D; ++i)
 
  973     bv.dist(i) = (std::numeric_limits<CoalScalar>::max)();
 
  977       bv.dist(0) = bv.dist(
D) = 
d;
 
  979       bv.dist(0) = bv.dist(
D) = -
d;
 
  982       bv.dist(1) = bv.dist(
D + 1) = 
d;
 
  984       bv.dist(1) = bv.dist(
D + 1) = -
d;
 
  987       bv.dist(2) = bv.dist(
D + 2) = 
d;
 
  989       bv.dist(2) = bv.dist(
D + 2) = -
d;
 
  990   } 
else if (n[2] == (
CoalScalar)0.0 && n[0] == n[1]) {
 
  991     bv.dist(3) = bv.dist(
D + 3) = n[0] * 
d * 2;
 
  992   } 
else if (n[1] == (
CoalScalar)0.0 && n[0] == n[2]) {
 
  993     bv.dist(4) = bv.dist(
D + 4) = n[0] * 
d * 2;
 
  994   } 
else if (n[0] == (
CoalScalar)0.0 && n[1] == n[2]) {
 
  995     bv.dist(5) = bv.dist(
D + 5) = n[1] * 
d * 2;
 
  997     bv.dist(6) = bv.dist(
D + 6) = n[0] * 
d * 2;
 
  999     bv.dist(7) = bv.dist(
D + 7) = n[0] * 
d * 2;
 
 1001     bv.dist(8) = bv.dist(
D + 8) = n[1] * 
d * 2;
 
 1003     bv.dist(9) = bv.dist(
D + 9) = n[0] * 
d * 3;
 
 1005     bv.dist(10) = bv.dist(
D + 10) = n[0] * 
d * 3;
 
 1007     bv.dist(11) = bv.dist(
D + 11) = n[1] * 
d * 3;
 
  
RSS rss
RSS member, for distance.
COAL_DLLAPI void computeBV< RSS, Halfspace >(const Halfspace &s, const Transform3s &tf, RSS &bv)
COAL_DLLAPI void computeBV< AABB, Plane >(const Plane &s, const Transform3s &tf, AABB &bv)
CoalScalar halfLength
Half Length along z axis.
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
COAL_DLLAPI void computeBV< AABB, Capsule >(const Capsule &s, const Transform3s &tf, AABB &bv)
COAL_DLLAPI void computeBV< kIOS, Halfspace >(const Halfspace &s, const Transform3s &tf, kIOS &bv)
COAL_DLLAPI void computeBV< OBB, Halfspace >(const Halfspace &s, const Transform3s &tf, OBB &bv)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Vec3s o
CoalScalar depth() const
Depth of the RSS.
COAL_DLLAPI void computeBV< OBB, ConvexBase >(const ConvexBase &s, const Transform3s &tf, OBB &bv)
COAL_DLLAPI std::array< Halfspace, 2 > transformToHalfspaces(const Plane &a, const Transform3s &tf)
CoalScalar halfLength
Half Length along z axis.
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
Vec3s extent
Half dimensions of OBB.
COAL_DLLAPI void computeBV< AABB, Halfspace >(const Halfspace &s, const Transform3s &tf, AABB &bv)
COAL_DLLAPI void computeBV< OBB, Plane >(const Plane &s, const Transform3s &tf, OBB &bv)
Capsule It is  where  is the distance between the point x and the capsule segment AB,...
CoalScalar radius
Radius of the cylinder.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Matrix3s axes
Orientation of OBB. axis[i] is the ith column of the orientation matrix for the box; it is also the i...
COAL_DLLAPI void computeBV< OBB, Cylinder >(const Cylinder &s, const Transform3s &tf, OBB &bv)
CoalScalar radius
Radius of sphere summed with rectangle to form RSS.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW OBB obb
OBB member, for rotation.
COAL_DLLAPI void computeBV< AABB, Cone >(const Cone &s, const Transform3s &tf, AABB &bv)
CoalScalar width() const
Width of the RSS.
CoalScalar length[2]
Side lengths of rectangle.
COAL_DLLAPI void computeBV< OBBRSS, Plane >(const Plane &s, const Transform3s &tf, OBBRSS &bv)
void fit(Vec3s *ps, unsigned int n, BV &bv)
Compute a bounding volume that fits a set of n points.
A class describing the kIOS collision structure, which is a set of spheres.
Ellipsoid centered at point zero.
kIOS_Sphere spheres[max_num_spheres]
The (at most) five spheres for intersection.
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Vec3s center() const
The (AABB) center.
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....
COAL_DLLAPI void computeBV< AABB, Cylinder >(const Cylinder &s, const Transform3s &tf, AABB &bv)
Center at zero point, axis aligned box.
COAL_DLLAPI void computeBV< OBB, Box >(const Box &s, const Transform3s &tf, OBB &bv)
Center at zero point sphere.
Vec3s max_
The max point in the AABB.
COAL_DLLAPI void constructBox(const AABB &bv, Box &box, Transform3s &tf)
construct a box shape (with a configuration) from a given bounding volume
CoalScalar halfLength
Half Length along z axis.
COAL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3s &tf)
#define COAL_THROW_PRETTY(message, exception)
COAL_DLLAPI void computeBV< OBB, Capsule >(const Capsule &s, const Transform3s &tf, OBB &bv)
COAL_DLLAPI void computeBV< RSS, Plane >(const Plane &s, const Transform3s &tf, RSS &bv)
unsigned int num_spheres
The number of spheres, no larger than 5.
Cylinder along Z axis. The cylinder is defined at its centroid.
std::vector< Vec3s > getBoundVertices(const Box &box, const Transform3s &tf)
COAL_DLLAPI void computeBV< AABB, Box >(const Box &s, const Transform3s &tf, AABB &bv)
Vec3s center() const
Center of the AABB.
Triangle stores the points instead of only indices of points.
KDOP class describes the KDOP collision structures. K is set as the template parameter,...
Vec3s min_
The min point in the AABB.
COAL_DLLAPI void computeBV< OBBRSS, Halfspace >(const Halfspace &s, const Transform3s &tf, OBBRSS &bv)
COAL_DLLAPI void computeBV< AABB, Sphere >(const Sphere &s, const Transform3s &tf, AABB &bv)
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 .
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Matrix3s axes
Orientation of RSS. axis[i] is the ith column of the orientation matrix for the RSS; it is also the i...
Vec3s halfSide
box side half-length
CoalScalar depth() const
The (AABB) depth.
COAL_DLLAPI void computeBV< OBB, Cone >(const Cone &s, const Transform3s &tf, OBB &bv)
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
CoalScalar radius
Radius of the sphere.
CoalScalar radius
Radius of the cone.
CoalScalar d
Plane offset.
OBB obb
@ OBB related with kIOS
CoalScalar height() const
Height of the RSS.
void setSweptSphereRadius(CoalScalar radius)
Set radius of sphere swept around the shape. Must be >= 0.
CoalScalar radius
Radius of capsule.
COAL_DLLAPI void computeBV< kIOS, Plane >(const Plane &s, const Transform3s &tf, kIOS &bv)
Vec3s Tr
Origin of the rectangle in RSS.
CoalScalar height() const
The (AABB) height.
Oriented bounding box class.
COAL_DLLAPI void computeBV< OBB, Sphere >(const Sphere &s, const Transform3s &tf, OBB &bv)
COAL_DLLAPI void computeBV< AABB, Ellipsoid >(const Ellipsoid &e, const Transform3s &tf, AABB &bv)
std::shared_ptr< std::vector< Vec3s > > points
An array of the points of the polygon.
CoalScalar width() const
The (AABB) width.
void generateCoordinateSystem(const Eigen::MatrixBase< Derived1 > &_w, const Eigen::MatrixBase< Derived2 > &_u, const Eigen::MatrixBase< Derived3 > &_v)
COAL_DLLAPI void computeBV< AABB, TriangleP >(const TriangleP &s, const Transform3s &tf, AABB &bv)
COAL_DLLAPI void computeBV< AABB, ConvexBase >(const ConvexBase &s, const Transform3s &tf, AABB &bv)
CoalScalar d
Plane offset.
Base for convex polytope.
hpp-fcl
Author(s): 
autogenerated on Fri Feb 14 2025 03:45:50