shape/geometric_shapes.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef HPP_FCL_GEOMETRIC_SHAPES_H
39 #define HPP_FCL_GEOMETRIC_SHAPES_H
40 
41 #include <boost/math/constants/constants.hpp>
42 
44 #include <hpp/fcl/data_types.h>
45 #include <string.h>
46 
47 namespace hpp {
48 namespace fcl {
49 
51 class HPP_FCL_DLLAPI ShapeBase : public CollisionGeometry {
52  public:
53  ShapeBase() {}
54 
56  ShapeBase(const ShapeBase& other) : CollisionGeometry(other) {}
57 
58  ShapeBase& operator=(const ShapeBase& other) = default;
59 
60  virtual ~ShapeBase(){};
61 
63  OBJECT_TYPE getObjectType() const { return OT_GEOM; }
64 };
65 
69 
71 class HPP_FCL_DLLAPI TriangleP : public ShapeBase {
72  public:
73  TriangleP(){};
74 
75  TriangleP(const Vec3f& a_, const Vec3f& b_, const Vec3f& c_)
76  : ShapeBase(), a(a_), b(b_), c(c_) {}
77 
78  TriangleP(const TriangleP& other)
79  : ShapeBase(other), a(other.a), b(other.b), c(other.c) {}
80 
82  virtual TriangleP* clone() const { return new TriangleP(*this); };
83 
85  void computeLocalAABB();
86 
87  NODE_TYPE getNodeType() const { return GEOM_TRIANGLE; }
88 
89  // std::pair<ShapeBase*, Transform3f> inflated(const FCL_REAL value) const {
90  // if (value == 0) return std::make_pair(new TriangleP(*this),
91  // Transform3f()); Vec3f AB(b - a), BC(c - b), CA(a - c); AB.normalize();
92  // BC.normalize();
93  // CA.normalize();
94  //
95  // Vec3f new_a(a + value * Vec3f(-AB + CA).normalized());
96  // Vec3f new_b(b + value * Vec3f(-BC + AB).normalized());
97  // Vec3f new_c(c + value * Vec3f(-CA + BC).normalized());
98  //
99  // return std::make_pair(new TriangleP(new_a, new_b, new_c),
100  // Transform3f());
101  // }
102  //
103  // FCL_REAL minInflationValue() const
104  // {
105  // return (std::numeric_limits<FCL_REAL>::max)(); // TODO(jcarpent):
106  // implement
107  // }
108 
109  Vec3f a, b, c;
110 
111  private:
112  virtual bool isEqual(const CollisionGeometry& _other) const {
113  const TriangleP* other_ptr = dynamic_cast<const TriangleP*>(&_other);
114  if (other_ptr == nullptr) return false;
115  const TriangleP& other = *other_ptr;
116 
117  return a == other.a && b == other.b && c == other.c;
118  }
119 
120  public:
121  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
122 };
123 
125 class HPP_FCL_DLLAPI Box : public ShapeBase {
126  public:
128  : ShapeBase(), halfSide(x / 2, y / 2, z / 2) {}
129 
130  Box(const Vec3f& side_) : ShapeBase(), halfSide(side_ / 2) {}
131 
132  Box(const Box& other) : ShapeBase(other), halfSide(other.halfSide) {}
133 
134  Box& operator=(const Box& other) {
135  if (this == &other) return *this;
136 
137  this->halfSide = other.halfSide;
138  return *this;
139  }
140 
142  virtual Box* clone() const { return new Box(*this); };
143 
145  Box() {}
146 
149 
151  void computeLocalAABB();
152 
154  NODE_TYPE getNodeType() const { return GEOM_BOX; }
155 
156  FCL_REAL computeVolume() const { return 8 * halfSide.prod(); }
157 
159  FCL_REAL V = computeVolume();
160  Vec3f s(halfSide.cwiseAbs2() * V);
161  return (Vec3f(s[1] + s[2], s[0] + s[2], s[0] + s[1]) / 3).asDiagonal();
162  }
163 
164  FCL_REAL minInflationValue() const { return -halfSide.minCoeff(); }
165 
172  std::pair<Box, Transform3f> inflated(const FCL_REAL value) const {
173  if (value <= minInflationValue())
174  HPP_FCL_THROW_PRETTY("value (" << value << ") "
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))),
179  Transform3f());
180  }
181 
182  private:
183  virtual bool isEqual(const CollisionGeometry& _other) const {
184  const Box* other_ptr = dynamic_cast<const Box*>(&_other);
185  if (other_ptr == nullptr) return false;
186  const Box& other = *other_ptr;
187 
188  return halfSide == other.halfSide;
189  }
190 
191  public:
192  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
193 };
194 
196 class HPP_FCL_DLLAPI Sphere : public ShapeBase {
197  public:
199  Sphere() {}
200 
201  explicit Sphere(FCL_REAL radius_) : ShapeBase(), radius(radius_) {}
202 
203  Sphere(const Sphere& other) : ShapeBase(other), radius(other.radius) {}
204 
206  virtual Sphere* clone() const { return new Sphere(*this); };
207 
210 
212  void computeLocalAABB();
213 
215  NODE_TYPE getNodeType() const { return GEOM_SPHERE; }
216 
218  FCL_REAL I = 0.4 * radius * radius * computeVolume();
219  return I * Matrix3f::Identity();
220  }
221 
223  return 4 * boost::math::constants::pi<FCL_REAL>() * radius * radius *
224  radius / 3;
225  }
226 
227  FCL_REAL minInflationValue() const { return -radius; }
228 
235  std::pair<Sphere, Transform3f> inflated(const FCL_REAL value) const {
236  if (value <= minInflationValue())
238  "value (" << value << ") is two small. It should be at least: "
239  << minInflationValue(),
240  std::invalid_argument);
241  return std::make_pair(Sphere(radius + value), Transform3f());
242  }
243 
244  private:
245  virtual bool isEqual(const CollisionGeometry& _other) const {
246  const Sphere* other_ptr = dynamic_cast<const Sphere*>(&_other);
247  if (other_ptr == nullptr) return false;
248  const Sphere& other = *other_ptr;
249 
250  return radius == other.radius;
251  }
252 
253  public:
254  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
255 };
256 
258 class HPP_FCL_DLLAPI Ellipsoid : public ShapeBase {
259  public:
262 
264  : ShapeBase(), radii(rx, ry, rz) {}
265 
266  explicit Ellipsoid(const Vec3f& radii) : radii(radii) {}
267 
268  Ellipsoid(const Ellipsoid& other) : ShapeBase(other), radii(other.radii) {}
269 
271  virtual Ellipsoid* clone() const { return new Ellipsoid(*this); };
272 
275  Vec3f radii;
276 
278  void computeLocalAABB();
279 
282 
284  FCL_REAL V = computeVolume();
285  FCL_REAL a2 = V * radii[0] * radii[0];
286  FCL_REAL b2 = V * radii[1] * radii[1];
287  FCL_REAL c2 = V * radii[2] * radii[2];
288  return (Matrix3f() << 0.2 * (b2 + c2), 0, 0, 0, 0.2 * (a2 + c2), 0, 0, 0,
289  0.2 * (a2 + b2))
290  .finished();
291  }
292 
294  return 4 * boost::math::constants::pi<FCL_REAL>() * radii[0] * radii[1] *
295  radii[2] / 3;
296  }
297 
298  FCL_REAL minInflationValue() const { return -radii.minCoeff(); }
299 
306  std::pair<Ellipsoid, Transform3f> inflated(const FCL_REAL value) const {
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)),
313  Transform3f());
314  }
315 
316  private:
317  virtual bool isEqual(const CollisionGeometry& _other) const {
318  const Ellipsoid* other_ptr = dynamic_cast<const Ellipsoid*>(&_other);
319  if (other_ptr == nullptr) return false;
320  const Ellipsoid& other = *other_ptr;
321 
322  return radii == other.radii;
323  }
324 
325  public:
326  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
327 };
328 
333 class HPP_FCL_DLLAPI Capsule : public ShapeBase {
334  public:
336  Capsule() {}
337 
338  Capsule(FCL_REAL radius_, FCL_REAL lz_) : ShapeBase(), radius(radius_) {
339  halfLength = lz_ / 2;
340  }
341 
342  Capsule(const Capsule& other)
343  : ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
344 
346  virtual Capsule* clone() const { return new Capsule(*this); };
347 
350 
353 
355  void computeLocalAABB();
356 
358  NODE_TYPE getNodeType() const { return GEOM_CAPSULE; }
359 
361  return boost::math::constants::pi<FCL_REAL>() * radius * radius *
362  ((halfLength * 2) + radius * 4 / 3.0);
363  }
364 
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;
370 
371  FCL_REAL h2 = halfLength * halfLength;
372  FCL_REAL r2 = radius * radius;
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;
376 
377  return (Matrix3f() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
378  }
379 
380  FCL_REAL minInflationValue() const { return -radius; }
381 
388  std::pair<Capsule, Transform3f> inflated(const FCL_REAL value) const {
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),
395  Transform3f());
396  }
397 
398  private:
399  virtual bool isEqual(const CollisionGeometry& _other) const {
400  const Capsule* other_ptr = dynamic_cast<const Capsule*>(&_other);
401  if (other_ptr == nullptr) return false;
402  const Capsule& other = *other_ptr;
403 
404  return radius == other.radius && halfLength == other.halfLength;
405  }
406 
407  public:
408  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
409 };
410 
414 class HPP_FCL_DLLAPI Cone : public ShapeBase {
415  public:
417  Cone() {}
418 
419  Cone(FCL_REAL radius_, FCL_REAL lz_) : ShapeBase(), radius(radius_) {
420  halfLength = lz_ / 2;
421  }
422 
423  Cone(const Cone& other)
424  : ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
425 
427  virtual Cone* clone() const { return new Cone(*this); };
428 
431 
434 
436  void computeLocalAABB();
437 
439  NODE_TYPE getNodeType() const { return GEOM_CONE; }
440 
442  return boost::math::constants::pi<FCL_REAL>() * radius * radius *
443  (halfLength * 2) / 3;
444  }
445 
447  FCL_REAL V = computeVolume();
448  FCL_REAL ix =
449  V * (0.4 * halfLength * halfLength + 3 * radius * radius / 20);
450  FCL_REAL iz = 0.3 * V * radius * radius;
451 
452  return (Matrix3f() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
453  }
454 
455  Vec3f computeCOM() const { return Vec3f(0, 0, -0.5 * halfLength); }
456 
457  FCL_REAL minInflationValue() const { return -(std::min)(radius, halfLength); }
458 
465  std::pair<Cone, Transform3f> inflated(const FCL_REAL value) const {
466  if (value <= minInflationValue())
468  "value (" << value << ") is two small. It should be at least: "
469  << minInflationValue(),
470  std::invalid_argument);
471 
472  // tan(alpha) = 2*halfLength/radius;
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;
477 
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;
481 
482  return std::make_pair(Cone(new_radius, new_lz),
483  Transform3f(Vec3f(0., 0., new_cz)));
484  }
485 
486  private:
487  virtual bool isEqual(const CollisionGeometry& _other) const {
488  const Cone* other_ptr = dynamic_cast<const Cone*>(&_other);
489  if (other_ptr == nullptr) return false;
490  const Cone& other = *other_ptr;
491 
492  return radius == other.radius && halfLength == other.halfLength;
493  }
494 
495  public:
496  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
497 };
498 
501 class HPP_FCL_DLLAPI Cylinder : public ShapeBase {
502  public:
504  Cylinder() {}
505 
506  Cylinder(FCL_REAL radius_, FCL_REAL lz_) : ShapeBase(), radius(radius_) {
507  halfLength = lz_ / 2;
508  }
509 
510  Cylinder(const Cylinder& other)
511  : ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
512 
513  Cylinder& operator=(const Cylinder& other) {
514  if (this == &other) return *this;
515 
516  this->radius = other.radius;
517  this->halfLength = other.halfLength;
518  return *this;
519  }
520 
522  virtual Cylinder* clone() const { return new Cylinder(*this); };
523 
526 
529 
531  void computeLocalAABB();
532 
534  NODE_TYPE getNodeType() const { return GEOM_CYLINDER; }
535 
537  return boost::math::constants::pi<FCL_REAL>() * radius * radius *
538  (halfLength * 2);
539  }
540 
542  FCL_REAL V = computeVolume();
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();
546  }
547 
548  FCL_REAL minInflationValue() const { return -(std::min)(radius, halfLength); }
549 
556  std::pair<Cylinder, Transform3f> inflated(const FCL_REAL value) const {
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)),
563  Transform3f());
564  }
565 
566  private:
567  virtual bool isEqual(const CollisionGeometry& _other) const {
568  const Cylinder* other_ptr = dynamic_cast<const Cylinder*>(&_other);
569  if (other_ptr == nullptr) return false;
570  const Cylinder& other = *other_ptr;
571 
572  return radius == other.radius && halfLength == other.halfLength;
573  }
574 
575  public:
576  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
577 };
578 
581 class HPP_FCL_DLLAPI ConvexBase : public ShapeBase {
582  public:
595  static ConvexBase* convexHull(const Vec3f* points, unsigned int num_points,
596  bool keepTriangles,
597  const char* qhullCommand = NULL);
598 
599  virtual ~ConvexBase();
600 
602  virtual ConvexBase* clone() const {
603  ConvexBase* copy_ptr = new ConvexBase(*this);
604  ConvexBase& copy = *copy_ptr;
605 
606  if (!copy.own_storage_) {
607  copy.points = new Vec3f[copy.num_points];
608  std::copy(points, points + num_points, copy.points);
609  }
610  copy.own_storage_ = true;
611  copy.ShapeBase::operator=(*this);
612 
613  return copy_ptr;
614  }
615 
617  void computeLocalAABB();
618 
620  NODE_TYPE getNodeType() const { return GEOM_CONVEX; }
621 
624  unsigned int num_points;
625 
626  struct HPP_FCL_DLLAPI Neighbors {
627  unsigned char count_;
628  unsigned int* n_;
629 
630  unsigned char const& count() const { return count_; }
631  unsigned int& operator[](int i) {
632  assert(i < count_);
633  return n_[i];
634  }
635  unsigned int const& operator[](int i) const {
636  assert(i < count_);
637  return n_[i];
638  }
639 
640  bool operator==(const Neighbors& other) const {
641  if (count_ != other.count_) return false;
642 
643  for (int i = 0; i < count_; ++i) {
644  if (n_[i] != other.n_[i]) return false;
645  }
646 
647  return true;
648  }
649 
650  bool operator!=(const Neighbors& other) const { return !(*this == other); }
651  };
656 
660 
661  protected:
665  : ShapeBase(),
666  points(NULL),
667  num_points(0),
668  neighbors(NULL),
669  nneighbors_(NULL),
670  own_storage_(false) {}
671 
678  void initialize(bool ownStorage, Vec3f* points_, unsigned int num_points_);
679 
685  void set(bool ownStorage, Vec3f* points_, unsigned int num_points_);
686 
689  ConvexBase(const ConvexBase& other);
690 
691  unsigned int* nneighbors_;
692 
694 
695  private:
696  void computeCenter();
697 
698  private:
699  virtual bool isEqual(const CollisionGeometry& _other) const {
700  const ConvexBase* other_ptr = dynamic_cast<const ConvexBase*>(&_other);
701  if (other_ptr == nullptr) return false;
702  const ConvexBase& other = *other_ptr;
703 
704  if (num_points != other.num_points) return false;
705 
706  for (unsigned int i = 0; i < num_points; ++i) {
707  if (points[i] != other.points[i]) return false;
708  }
709 
710  for (unsigned int i = 0; i < num_points; ++i) {
711  if (neighbors[i] != other.neighbors[i]) return false;
712  }
713 
714  return center == other.center;
715  }
716 
717  public:
718  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
719 };
720 
721 template <typename PolygonT>
722 class Convex;
723 
729 class HPP_FCL_DLLAPI Halfspace : public ShapeBase {
730  public:
732  Halfspace(const Vec3f& n_, FCL_REAL d_) : ShapeBase(), n(n_), d(d_) {
733  unitNormalTest();
734  }
735 
738  : ShapeBase(), n(a, b, c), d(d_) {
739  unitNormalTest();
740  }
741 
742  Halfspace() : ShapeBase(), n(1, 0, 0), d(0) {}
743 
744  Halfspace(const Halfspace& other)
745  : ShapeBase(other), n(other.n), d(other.d) {}
746 
748  Halfspace& operator=(const Halfspace& other) {
749  n = other.n;
750  d = other.d;
751  return *this;
752  }
753 
755  virtual Halfspace* clone() const { return new Halfspace(*this); };
756 
757  FCL_REAL signedDistance(const Vec3f& p) const { return n.dot(p) - d; }
758 
759  FCL_REAL distance(const Vec3f& p) const { return std::abs(n.dot(p) - d); }
760 
762  void computeLocalAABB();
763 
766 
768  return std::numeric_limits<FCL_REAL>::lowest();
769  }
770 
777  std::pair<Halfspace, Transform3f> inflated(const FCL_REAL value) const {
778  if (value <= minInflationValue())
780  "value (" << value << ") is two small. It should be at least: "
781  << minInflationValue(),
782  std::invalid_argument);
783  return std::make_pair(Halfspace(n, d + value), Transform3f());
784  }
785 
788 
791 
792  protected:
794  void unitNormalTest();
795 
796  private:
797  virtual bool isEqual(const CollisionGeometry& _other) const {
798  const Halfspace* other_ptr = dynamic_cast<const Halfspace*>(&_other);
799  if (other_ptr == nullptr) return false;
800  const Halfspace& other = *other_ptr;
801 
802  return n == other.n && d == other.d;
803  }
804 
805  public:
806  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
807 };
808 
810 class HPP_FCL_DLLAPI Plane : public ShapeBase {
811  public:
813  Plane(const Vec3f& n_, FCL_REAL d_) : ShapeBase(), n(n_), d(d_) {
814  unitNormalTest();
815  }
816 
819  : ShapeBase(), n(a, b, c), d(d_) {
820  unitNormalTest();
821  }
822 
823  Plane() : ShapeBase(), n(1, 0, 0), d(0) {}
824 
825  Plane(const Plane& other) : ShapeBase(other), n(other.n), d(other.d) {}
826 
828  Plane& operator=(const Plane& other) {
829  n = other.n;
830  d = other.d;
831  return *this;
832  }
833 
835  virtual Plane* clone() const { return new Plane(*this); };
836 
837  FCL_REAL signedDistance(const Vec3f& p) const { return n.dot(p) - d; }
838 
839  FCL_REAL distance(const Vec3f& p) const { return std::abs(n.dot(p) - d); }
840 
842  void computeLocalAABB();
843 
845  NODE_TYPE getNodeType() const { return GEOM_PLANE; }
846 
849 
852 
853  protected:
855  void unitNormalTest();
856 
857  private:
858  virtual bool isEqual(const CollisionGeometry& _other) const {
859  const Plane* other_ptr = dynamic_cast<const Plane*>(&_other);
860  if (other_ptr == nullptr) return false;
861  const Plane& other = *other_ptr;
862 
863  return n == other.n && d == other.d;
864  }
865 
866  public:
867  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
868 };
869 
870 } // namespace fcl
871 
872 } // namespace hpp
873 
874 #endif
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.
V
Vec3f halfSide
box side half-length
NODE_TYPE getNodeType() const
Get node type: a box.
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
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.
Sphere(FCL_REAL radius_)
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Cylinder along Z axis. The cylinder is defined at its centroid.
Main namespace.
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
Definition: data_types.h:68
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.
c
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.
double FCL_REAL
Definition: data_types.h:65
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
FCL_REAL d
Plane offset.
FCL_REAL minInflationValue() const
FCL_REAL d
Plane offset.
FCL_REAL radius
Radius of the sphere.
Ellipsoid(const Vec3f &radii)
Cone(const Cone &other)
FCL_REAL radius
Radius of the cylinder.
Vec3f n
Plane normal.
Box(const Vec3f &side_)
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
r2
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.
c2
list a
Box(const Box &other)
Cylinder(const Cylinder &other)
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
Vec3f radii
Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2.
Convex polytope.
Definition: shape/convex.h:50
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.
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)


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:01