38 #ifndef FCL_SHAPE_SPHERE_INL_H 39 #define FCL_SHAPE_SPHERE_INL_H 100 std::vector<Vector3<S>> result(12);
101 const auto m = (1 + std::sqrt(5.0)) / 2.0;
102 auto edge_size =
radius * 6 / (std::sqrt(27.0) + std::sqrt(15.0));
105 auto b = m * edge_size;
107 result[1] = tf * Vector3<S>(0, -a, b);
108 result[2] = tf * Vector3<S>(0, a, -b);
109 result[3] = tf * Vector3<S>(0, -a, -b);
110 result[4] = tf * Vector3<S>(a, b, 0);
111 result[5] = tf * Vector3<S>(-a, b, 0);
112 result[6] = tf * Vector3<S>(a, -b, 0);
113 result[7] = tf * Vector3<S>(-a, -b, 0);
114 result[8] = tf * Vector3<S>(b, 0, a);
115 result[9] = tf * Vector3<S>(b, 0, -a);
116 result[10] = tf * Vector3<S>(-b, 0, a);
117 result[11] = tf * Vector3<S>(-b, 0, -a);
123 template <
typename S>
126 std::stringstream ss;
127 ss << std::setprecision(precision);
128 ss <<
"Sphere<" << S_str <<
">(" <<
radius <<
");";
Vector3< S_ > aabb_center
AABB center in local coordinate.
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, halfspace, triangle), and octree
Base class for all basic geometric shapes.
S_ aabb_radius
AABB radius.
static const char * value()
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Eigen::Matrix< S, 3, 3 > Matrix3
Matrix3< S > computeMomentofInertia() const override
compute the inertia matrix, related to the origin
Eigen::Matrix< S, 3, 1 > Vector3
std::string representation(int precision=20) const
Create a string that should be sufficient to recreate this shape. This is akin to the repr() implemen...
static constexpr S pi()
The mathematical constant pi.
AABB< S_ > aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
void computeLocalAABB() override
Compute AABB<S>
S radius
Radius of the sphere.
std::vector< Vector3< S > > getBoundVertices(const Transform3< S > &tf) const
get the vertices of some convex shape which can bound this shape in a specific configuration ...
S computeVolume() const override
compute the volume
NODE_TYPE getNodeType() const override
Get node type: a sphere.
template class FCL_EXPORT Sphere< double >