coal/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 COAL_GEOMETRIC_SHAPES_H
39 #define COAL_GEOMETRIC_SHAPES_H
40 
41 #include <vector>
42 #include <memory>
43 
44 #include <boost/math/constants/constants.hpp>
45 
46 #include "coal/collision_object.h"
47 #include "coal/data_types.h"
48 
49 #ifdef COAL_HAS_QHULL
50 namespace orgQhull {
51 class Qhull;
52 }
53 #endif
54 
55 namespace coal {
56 
58 class COAL_DLLAPI ShapeBase : public CollisionGeometry {
59  public:
60  ShapeBase() {}
61 
63  ShapeBase(const ShapeBase& other)
64  : CollisionGeometry(other),
65  m_swept_sphere_radius(other.m_swept_sphere_radius) {}
66 
67  ShapeBase& operator=(const ShapeBase& other) = default;
68 
69  virtual ~ShapeBase() {};
70 
72  OBJECT_TYPE getObjectType() const { return OT_GEOM; }
73 
77  if (radius < 0) {
78  COAL_THROW_PRETTY("Swept-sphere radius must be positive.",
79  std::invalid_argument);
80  }
81  this->m_swept_sphere_radius = radius;
82  }
83 
87  return this->m_swept_sphere_radius;
88  }
89 
90  protected:
102  CoalScalar m_swept_sphere_radius{0};
103 };
104 
108 
110 class COAL_DLLAPI TriangleP : public ShapeBase {
111  public:
112  TriangleP() {};
113 
114  TriangleP(const Vec3s& a_, const Vec3s& b_, const Vec3s& c_)
115  : ShapeBase(), a(a_), b(b_), c(c_) {}
116 
117  TriangleP(const TriangleP& other)
118  : ShapeBase(other), a(other.a), b(other.b), c(other.c) {}
119 
121  virtual TriangleP* clone() const { return new TriangleP(*this); };
122 
124  void computeLocalAABB();
125 
126  NODE_TYPE getNodeType() const { return GEOM_TRIANGLE; }
127 
128  // std::pair<ShapeBase*, Transform3s> inflated(const CoalScalar value) const
129  // {
130  // if (value == 0) return std::make_pair(new TriangleP(*this),
131  // Transform3s()); Vec3s AB(b - a), BC(c - b), CA(a - c); AB.normalize();
132  // BC.normalize();
133  // CA.normalize();
134  //
135  // Vec3s new_a(a + value * Vec3s(-AB + CA).normalized());
136  // Vec3s new_b(b + value * Vec3s(-BC + AB).normalized());
137  // Vec3s new_c(c + value * Vec3s(-CA + BC).normalized());
138  //
139  // return std::make_pair(new TriangleP(new_a, new_b, new_c),
140  // Transform3s());
141  // }
142  //
143  // CoalScalar minInflationValue() const
144  // {
145  // return (std::numeric_limits<CoalScalar>::max)(); // TODO(jcarpent):
146  // implement
147  // }
148 
149  Vec3s a, b, c;
150 
151  private:
152  virtual bool isEqual(const CollisionGeometry& _other) const {
153  const TriangleP* other_ptr = dynamic_cast<const TriangleP*>(&_other);
154  if (other_ptr == nullptr) return false;
155  const TriangleP& other = *other_ptr;
156 
157  return a == other.a && b == other.b && c == other.c &&
158  getSweptSphereRadius() == other.getSweptSphereRadius();
159  }
160 
161  public:
162  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
163 };
164 
166 class COAL_DLLAPI Box : public ShapeBase {
167  public:
169  : ShapeBase(), halfSide(x / 2, y / 2, z / 2) {}
170 
171  Box(const Vec3s& side_) : ShapeBase(), halfSide(side_ / 2) {}
172 
173  Box(const Box& other) : ShapeBase(other), halfSide(other.halfSide) {}
174 
175  Box& operator=(const Box& other) {
176  if (this == &other) return *this;
177 
178  this->halfSide = other.halfSide;
179  return *this;
180  }
181 
183  virtual Box* clone() const { return new Box(*this); };
184 
186  Box() {}
187 
190 
192  void computeLocalAABB();
193 
195  NODE_TYPE getNodeType() const { return GEOM_BOX; }
196 
197  CoalScalar computeVolume() const { return 8 * halfSide.prod(); }
198 
200  CoalScalar V = computeVolume();
201  Vec3s s(halfSide.cwiseAbs2() * V);
202  return (Vec3s(s[1] + s[2], s[0] + s[2], s[0] + s[1]) / 3).asDiagonal();
203  }
204 
205  CoalScalar minInflationValue() const { return -halfSide.minCoeff(); }
206 
215  std::pair<Box, Transform3s> inflated(const CoalScalar value) const {
216  if (value <= minInflationValue())
217  COAL_THROW_PRETTY("value (" << value << ") "
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))),
222  Transform3s());
223  }
224 
225  private:
226  virtual bool isEqual(const CollisionGeometry& _other) const {
227  const Box* other_ptr = dynamic_cast<const Box*>(&_other);
228  if (other_ptr == nullptr) return false;
229  const Box& other = *other_ptr;
230 
231  return halfSide == other.halfSide &&
232  getSweptSphereRadius() == other.getSweptSphereRadius();
233  }
234 
235  public:
236  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
237 };
238 
240 class COAL_DLLAPI Sphere : public ShapeBase {
241  public:
243  Sphere() {}
244 
245  explicit Sphere(CoalScalar radius_) : ShapeBase(), radius(radius_) {}
246 
247  Sphere(const Sphere& other) : ShapeBase(other), radius(other.radius) {}
248 
250  virtual Sphere* clone() const { return new Sphere(*this); };
251 
253  CoalScalar radius;
254 
256  void computeLocalAABB();
257 
259  NODE_TYPE getNodeType() const { return GEOM_SPHERE; }
260 
262  CoalScalar I = 0.4 * radius * radius * computeVolume();
263  return I * Matrix3s::Identity();
264  }
265 
267  return 4 * boost::math::constants::pi<CoalScalar>() * radius * radius *
268  radius / 3;
269  }
270 
271  CoalScalar minInflationValue() const { return -radius; }
272 
281  std::pair<Sphere, Transform3s> inflated(const CoalScalar value) const {
282  if (value <= minInflationValue())
283  COAL_THROW_PRETTY("value (" << value
284  << ") is two small. It should be at least: "
285  << minInflationValue(),
286  std::invalid_argument);
287  return std::make_pair(Sphere(radius + value), Transform3s());
288  }
289 
290  private:
291  virtual bool isEqual(const CollisionGeometry& _other) const {
292  const Sphere* other_ptr = dynamic_cast<const Sphere*>(&_other);
293  if (other_ptr == nullptr) return false;
294  const Sphere& other = *other_ptr;
295 
296  return radius == other.radius &&
297  getSweptSphereRadius() == other.getSweptSphereRadius();
298  }
299 
300  public:
301  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
302 };
303 
305 class COAL_DLLAPI Ellipsoid : public ShapeBase {
306  public:
309 
311  : ShapeBase(), radii(rx, ry, rz) {}
312 
313  explicit Ellipsoid(const Vec3s& radii) : radii(radii) {}
314 
315  Ellipsoid(const Ellipsoid& other) : ShapeBase(other), radii(other.radii) {}
316 
318  virtual Ellipsoid* clone() const { return new Ellipsoid(*this); };
319 
322  Vec3s radii;
323 
325  void computeLocalAABB();
326 
329 
331  CoalScalar V = computeVolume();
332  CoalScalar a2 = V * radii[0] * radii[0];
333  CoalScalar b2 = V * radii[1] * radii[1];
334  CoalScalar c2 = V * radii[2] * radii[2];
335  return (Matrix3s() << 0.2 * (b2 + c2), 0, 0, 0, 0.2 * (a2 + c2), 0, 0, 0,
336  0.2 * (a2 + b2))
337  .finished();
338  }
339 
341  return 4 * boost::math::constants::pi<CoalScalar>() * radii[0] * radii[1] *
342  radii[2] / 3;
343  }
344 
345  CoalScalar minInflationValue() const { return -radii.minCoeff(); }
346 
355  std::pair<Ellipsoid, Transform3s> inflated(const CoalScalar value) const {
356  if (value <= minInflationValue())
357  COAL_THROW_PRETTY("value (" << value
358  << ") is two small. It should be at least: "
359  << minInflationValue(),
360  std::invalid_argument);
361  return std::make_pair(Ellipsoid(radii + Vec3s::Constant(value)),
362  Transform3s());
363  }
364 
365  private:
366  virtual bool isEqual(const CollisionGeometry& _other) const {
367  const Ellipsoid* other_ptr = dynamic_cast<const Ellipsoid*>(&_other);
368  if (other_ptr == nullptr) return false;
369  const Ellipsoid& other = *other_ptr;
370 
371  return radii == other.radii &&
372  getSweptSphereRadius() == other.getSweptSphereRadius();
373  }
374 
375  public:
376  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
377 };
378 
383 class COAL_DLLAPI Capsule : public ShapeBase {
384  public:
386  Capsule() {}
387 
388  Capsule(CoalScalar radius_, CoalScalar lz_) : ShapeBase(), radius(radius_) {
389  halfLength = lz_ / 2;
390  }
391 
392  Capsule(const Capsule& other)
393  : ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
394 
396  virtual Capsule* clone() const { return new Capsule(*this); };
397 
399  CoalScalar radius;
400 
403 
405  void computeLocalAABB();
406 
408  NODE_TYPE getNodeType() const { return GEOM_CAPSULE; }
409 
411  return boost::math::constants::pi<CoalScalar>() * radius * radius *
412  ((halfLength * 2) + radius * 4 / 3.0);
413  }
414 
416  CoalScalar v_cyl = radius * radius * (halfLength * 2) *
417  boost::math::constants::pi<CoalScalar>();
418  CoalScalar v_sph = radius * radius * radius *
419  boost::math::constants::pi<CoalScalar>() * 4 / 3.0;
420 
421  CoalScalar h2 = halfLength * halfLength;
422  CoalScalar r2 = radius * radius;
423  CoalScalar ix = v_cyl * (h2 / 3. + r2 / 4.) +
424  v_sph * (0.4 * r2 + h2 + 0.75 * radius * halfLength);
425  CoalScalar iz = (0.5 * v_cyl + 0.4 * v_sph) * radius * radius;
426 
427  return (Matrix3s() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
428  }
429 
430  CoalScalar minInflationValue() const { return -radius; }
431 
440  std::pair<Capsule, Transform3s> inflated(const CoalScalar value) const {
441  if (value <= minInflationValue())
442  COAL_THROW_PRETTY("value (" << value
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),
447  Transform3s());
448  }
449 
450  private:
451  virtual bool isEqual(const CollisionGeometry& _other) const {
452  const Capsule* other_ptr = dynamic_cast<const Capsule*>(&_other);
453  if (other_ptr == nullptr) return false;
454  const Capsule& other = *other_ptr;
455 
456  return radius == other.radius && halfLength == other.halfLength &&
457  getSweptSphereRadius() == other.getSweptSphereRadius();
458  }
459 
460  public:
461  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
462 };
463 
467 class COAL_DLLAPI Cone : public ShapeBase {
468  public:
470  Cone() {}
471 
472  Cone(CoalScalar radius_, CoalScalar lz_) : ShapeBase(), radius(radius_) {
473  halfLength = lz_ / 2;
474  }
475 
476  Cone(const Cone& other)
477  : ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
478 
480  virtual Cone* clone() const { return new Cone(*this); };
481 
483  CoalScalar radius;
484 
487 
489  void computeLocalAABB();
490 
492  NODE_TYPE getNodeType() const { return GEOM_CONE; }
493 
495  return boost::math::constants::pi<CoalScalar>() * radius * radius *
496  (halfLength * 2) / 3;
497  }
498 
500  CoalScalar V = computeVolume();
501  CoalScalar ix =
502  V * (0.4 * halfLength * halfLength + 3 * radius * radius / 20);
503  CoalScalar iz = 0.3 * V * radius * radius;
504 
505  return (Matrix3s() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
506  }
507 
508  Vec3s computeCOM() const { return Vec3s(0, 0, -0.5 * halfLength); }
509 
511  return -(std::min)(radius, halfLength);
512  }
513 
522  std::pair<Cone, Transform3s> inflated(const CoalScalar value) const {
523  if (value <= minInflationValue())
524  COAL_THROW_PRETTY("value (" << value
525  << ") is two small. It should be at least: "
526  << minInflationValue(),
527  std::invalid_argument);
528 
529  // tan(alpha) = 2*halfLength/radius;
530  const CoalScalar tan_alpha = 2 * halfLength / radius;
531  const CoalScalar sin_alpha =
532  tan_alpha / std::sqrt(1 + tan_alpha * tan_alpha);
533  const CoalScalar top_inflation = value / sin_alpha;
534  const CoalScalar bottom_inflation = value;
535 
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;
539 
540  return std::make_pair(Cone(new_radius, new_lz),
541  Transform3s(Vec3s(0., 0., new_cz)));
542  }
543 
544  private:
545  virtual bool isEqual(const CollisionGeometry& _other) const {
546  const Cone* other_ptr = dynamic_cast<const Cone*>(&_other);
547  if (other_ptr == nullptr) return false;
548  const Cone& other = *other_ptr;
549 
550  return radius == other.radius && halfLength == other.halfLength &&
551  getSweptSphereRadius() == other.getSweptSphereRadius();
552  }
553 
554  public:
555  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
556 };
557 
560 class COAL_DLLAPI Cylinder : public ShapeBase {
561  public:
563  Cylinder() {}
564 
565  Cylinder(CoalScalar radius_, CoalScalar lz_) : ShapeBase(), radius(radius_) {
566  halfLength = lz_ / 2;
567  }
568 
569  Cylinder(const Cylinder& other)
570  : ShapeBase(other), radius(other.radius), halfLength(other.halfLength) {}
571 
572  Cylinder& operator=(const Cylinder& other) {
573  if (this == &other) return *this;
574 
575  this->radius = other.radius;
576  this->halfLength = other.halfLength;
577  return *this;
578  }
579 
581  virtual Cylinder* clone() const { return new Cylinder(*this); };
582 
584  CoalScalar radius;
585 
588 
590  void computeLocalAABB();
591 
593  NODE_TYPE getNodeType() const { return GEOM_CYLINDER; }
594 
596  return boost::math::constants::pi<CoalScalar>() * radius * radius *
597  (halfLength * 2);
598  }
599 
601  CoalScalar V = computeVolume();
602  CoalScalar ix = V * (radius * radius / 4 + halfLength * halfLength / 3);
603  CoalScalar iz = V * radius * radius / 2;
604  return (Matrix3s() << ix, 0, 0, 0, ix, 0, 0, 0, iz).finished();
605  }
606 
608  return -(std::min)(radius, halfLength);
609  }
610 
619  std::pair<Cylinder, Transform3s> inflated(const CoalScalar value) const {
620  if (value <= minInflationValue())
621  COAL_THROW_PRETTY("value (" << value
622  << ") is two small. It should be at least: "
623  << minInflationValue(),
624  std::invalid_argument);
625  return std::make_pair(Cylinder(radius + value, 2 * (halfLength + value)),
626  Transform3s());
627  }
628 
629  private:
630  virtual bool isEqual(const CollisionGeometry& _other) const {
631  const Cylinder* other_ptr = dynamic_cast<const Cylinder*>(&_other);
632  if (other_ptr == nullptr) return false;
633  const Cylinder& other = *other_ptr;
634 
635  return radius == other.radius && halfLength == other.halfLength &&
636  getSweptSphereRadius() == other.getSweptSphereRadius();
637  }
638 
639  public:
640  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
641 };
642 
645 class COAL_DLLAPI ConvexBase : public ShapeBase {
646  public:
659  static ConvexBase* convexHull(std::shared_ptr<std::vector<Vec3s>>& points,
660  unsigned int num_points, bool keepTriangles,
661  const char* qhullCommand = NULL);
662 
663  // TODO(louis): put this method in private sometime in the future.
664  COAL_DEPRECATED static ConvexBase* convexHull(
665  const Vec3s* points, unsigned int num_points, bool keepTriangles,
666  const char* qhullCommand = NULL);
667 
668  virtual ~ConvexBase();
669 
673  virtual ConvexBase* clone() const { return new ConvexBase(*this); }
674 
676  void computeLocalAABB();
677 
679  NODE_TYPE getNodeType() const { return GEOM_CONVEX; }
680 
681 #ifdef COAL_HAS_QHULL
682  void buildDoubleDescription();
685 #endif
686 
687  struct COAL_DLLAPI Neighbors {
688  unsigned char count_;
689  unsigned int* n_;
690 
691  unsigned char const& count() const { return count_; }
692  unsigned int& operator[](int i) {
693  assert(i < count_);
694  return n_[i];
695  }
696  unsigned int const& operator[](int i) const {
697  assert(i < count_);
698  return n_[i];
699  }
700 
701  bool operator==(const Neighbors& other) const {
702  if (count_ != other.count_) return false;
703 
704  for (int i = 0; i < count_; ++i) {
705  if (n_[i] != other.n_[i]) return false;
706  }
707 
708  return true;
709  }
710 
711  bool operator!=(const Neighbors& other) const { return !(*this == other); }
712  };
713 
716  static constexpr size_t num_vertices_large_convex_threshold = 32;
717 
719  std::shared_ptr<std::vector<Vec3s>> points;
720  unsigned int num_points;
721 
723  std::shared_ptr<std::vector<Vec3s>> normals;
726  std::shared_ptr<std::vector<double>> offsets;
728 
732  std::shared_ptr<std::vector<Neighbors>> neighbors;
733 
737 
745  std::vector<Vec3s> points;
746 
750  std::vector<int> indices;
751  };
752 
754  static constexpr size_t num_support_warm_starts = 14;
755 
758 
759  protected:
763  : ShapeBase(),
764  num_points(0),
765  num_normals_and_offsets(0),
766  center(Vec3s::Zero()) {}
767 
774  void initialize(std::shared_ptr<std::vector<Vec3s>> points_,
775  unsigned int num_points_);
776 
782  void set(std::shared_ptr<std::vector<Vec3s>> points_,
783  unsigned int num_points_);
784 
787  ConvexBase(const ConvexBase& other);
788 
789 #ifdef COAL_HAS_QHULL
790  void buildDoubleDescriptionFromQHullResult(const orgQhull::Qhull& qh);
791 #endif
792 
794  void buildSupportWarmStart();
795 
801  std::shared_ptr<std::vector<unsigned int>> nneighbors_;
802 
803  private:
804  void computeCenter();
805 
806  virtual bool isEqual(const CollisionGeometry& _other) const {
807  const ConvexBase* other_ptr = dynamic_cast<const ConvexBase*>(&_other);
808  if (other_ptr == nullptr) return false;
809  const ConvexBase& other = *other_ptr;
810 
811  if (num_points != other.num_points) return false;
812 
813  if ((!(points.get()) && other.points.get()) ||
814  (points.get() && !(other.points.get())))
815  return false;
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;
821  }
822  }
823 
824  if ((!(neighbors.get()) && other.neighbors.get()) ||
825  (neighbors.get() && !(other.neighbors.get())))
826  return false;
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;
832  }
833  }
834 
835  if ((!(normals.get()) && other.normals.get()) ||
836  (normals.get() && !(other.normals.get())))
837  return false;
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;
843  }
844  }
845 
846  if ((!(offsets.get()) && other.offsets.get()) ||
847  (offsets.get() && !(other.offsets.get())))
848  return false;
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;
854  }
855  }
856 
857  if (this->support_warm_starts.points.size() !=
858  other.support_warm_starts.points.size() ||
859  this->support_warm_starts.indices.size() !=
860  other.support_warm_starts.indices.size()) {
861  return false;
862  }
863 
864  for (size_t i = 0; i < this->support_warm_starts.points.size(); ++i) {
865  if (this->support_warm_starts.points[i] !=
866  other.support_warm_starts.points[i] ||
867  this->support_warm_starts.indices[i] !=
868  other.support_warm_starts.indices[i]) {
869  return false;
870  }
871  }
872 
873  return center == other.center &&
874  getSweptSphereRadius() == other.getSweptSphereRadius();
875  }
876 
877  public:
878  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
879 };
880 
881 template <typename PolygonT>
882 class Convex;
883 
892 class COAL_DLLAPI Halfspace : public ShapeBase {
893  public:
895  Halfspace(const Vec3s& n_, CoalScalar d_) : ShapeBase(), n(n_), d(d_) {
896  unitNormalTest();
897  }
898 
901  : ShapeBase(), n(a, b, c), d(d_) {
902  unitNormalTest();
903  }
904 
905  Halfspace() : ShapeBase(), n(1, 0, 0), d(0) {}
906 
907  Halfspace(const Halfspace& other)
908  : ShapeBase(other), n(other.n), d(other.d) {}
909 
911  Halfspace& operator=(const Halfspace& other) {
912  n = other.n;
913  d = other.d;
914  return *this;
915  }
916 
918  virtual Halfspace* clone() const { return new Halfspace(*this); };
919 
920  CoalScalar signedDistance(const Vec3s& p) const {
921  return n.dot(p) - (d + this->getSweptSphereRadius());
922  }
923 
924  CoalScalar distance(const Vec3s& p) const {
925  return std::abs(this->signedDistance(p));
926  }
927 
929  void computeLocalAABB();
930 
933 
935  return std::numeric_limits<CoalScalar>::lowest();
936  }
937 
946  std::pair<Halfspace, Transform3s> inflated(const CoalScalar value) const {
947  if (value <= minInflationValue())
948  COAL_THROW_PRETTY("value (" << value
949  << ") is two small. It should be at least: "
950  << minInflationValue(),
951  std::invalid_argument);
952  return std::make_pair(Halfspace(n, d + value), Transform3s());
953  }
954 
957 
960 
961  protected:
963  void unitNormalTest();
964 
965  private:
966  virtual bool isEqual(const CollisionGeometry& _other) const {
967  const Halfspace* other_ptr = dynamic_cast<const Halfspace*>(&_other);
968  if (other_ptr == nullptr) return false;
969  const Halfspace& other = *other_ptr;
970 
971  return n == other.n && d == other.d &&
972  getSweptSphereRadius() == other.getSweptSphereRadius();
973  }
974 
975  public:
976  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
977 };
978 
983 class COAL_DLLAPI Plane : public ShapeBase {
984  public:
986  Plane(const Vec3s& n_, CoalScalar d_) : ShapeBase(), n(n_), d(d_) {
987  unitNormalTest();
988  }
989 
992  : ShapeBase(), n(a, b, c), d(d_) {
993  unitNormalTest();
994  }
995 
996  Plane() : ShapeBase(), n(1, 0, 0), d(0) {}
997 
998  Plane(const Plane& other) : ShapeBase(other), n(other.n), d(other.d) {}
999 
1001  Plane& operator=(const Plane& other) {
1002  n = other.n;
1003  d = other.d;
1004  return *this;
1005  }
1006 
1008  virtual Plane* clone() const { return new Plane(*this); };
1009 
1010  CoalScalar signedDistance(const Vec3s& p) const {
1011  const CoalScalar dist = n.dot(p) - d;
1012  CoalScalar signed_dist =
1013  std::abs(n.dot(p) - d) - this->getSweptSphereRadius();
1014  if (dist >= 0) {
1015  return signed_dist;
1016  }
1017  if (signed_dist >= 0) {
1018  return -signed_dist;
1019  }
1020  return signed_dist;
1021  }
1022 
1023  CoalScalar distance(const Vec3s& p) const {
1024  return std::abs(std::abs(n.dot(p) - d) - this->getSweptSphereRadius());
1025  }
1026 
1028  void computeLocalAABB();
1029 
1031  NODE_TYPE getNodeType() const { return GEOM_PLANE; }
1032 
1035 
1038 
1039  protected:
1041  void unitNormalTest();
1042 
1043  private:
1044  virtual bool isEqual(const CollisionGeometry& _other) const {
1045  const Plane* other_ptr = dynamic_cast<const Plane*>(&_other);
1046  if (other_ptr == nullptr) return false;
1047  const Plane& other = *other_ptr;
1048 
1049  return n == other.n && d == other.d &&
1050  getSweptSphereRadius() == other.getSweptSphereRadius();
1051  }
1052 
1053  public:
1054  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
1055 };
1056 
1057 } // namespace coal
1058 
1059 #endif
coal::Box::getNodeType
NODE_TYPE getNodeType() const
Get node type: a box.
Definition: coal/shape/geometric_shapes.h:195
coal::Cone::inflated
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 ...
Definition: coal/shape/geometric_shapes.h:522
coal::Sphere::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:291
coal::Cylinder::inflated
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...
Definition: coal/shape/geometric_shapes.h:619
coal::TriangleP::b
Vec3s b
Definition: coal/shape/geometric_shapes.h:149
coal::Ellipsoid::Ellipsoid
Ellipsoid(const Ellipsoid &other)
Definition: coal/shape/geometric_shapes.h:315
coal::Cylinder::getNodeType
NODE_TYPE getNodeType() const
Get node type: a cylinder.
Definition: coal/shape/geometric_shapes.h:593
coal::Halfspace::inflated
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...
Definition: coal/shape/geometric_shapes.h:946
coal::Sphere::inflated
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...
Definition: coal/shape/geometric_shapes.h:281
coal::Cylinder::halfLength
CoalScalar halfLength
Half Length along z axis.
Definition: coal/shape/geometric_shapes.h:587
coal::TriangleP::clone
virtual TriangleP * clone() const
Clone *this into a new TriangleP.
Definition: coal/shape/geometric_shapes.h:121
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::Capsule::minInflationValue
CoalScalar minInflationValue() const
Definition: coal/shape/geometric_shapes.h:430
V
V
coal::ConvexBase::Neighbors::n_
unsigned int * n_
Definition: coal/shape/geometric_shapes.h:689
coal::Box::operator=
Box & operator=(const Box &other)
Definition: coal/shape/geometric_shapes.h:175
coal::ConvexBase::num_points
unsigned int num_points
Definition: coal/shape/geometric_shapes.h:720
coal::ConvexBase::getNodeType
NODE_TYPE getNodeType() const
Get node type: a convex polytope.
Definition: coal/shape/geometric_shapes.h:679
coal::Cone::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/shape/geometric_shapes.h:494
coal::Box::clone
virtual Box * clone() const
Clone *this into a new Box.
Definition: coal/shape/geometric_shapes.h:183
coal::ConvexBase::clone
virtual ConvexBase * clone() const
Clone (deep copy). This method is consistent with BVHModel clone method. The copy constructor is call...
Definition: coal/shape/geometric_shapes.h:673
coal::ConvexBase::Neighbors::operator==
bool operator==(const Neighbors &other) const
Definition: coal/shape/geometric_shapes.h:701
coal::Cylinder::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/shape/geometric_shapes.h:600
coal::ConvexBase::neighbors
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 ...
Definition: coal/shape/geometric_shapes.h:732
orgQhull
QhullRidge – Qhull's ridge structure, ridgeT, as a C++ class.
Definition: Coordinates.cpp:21
coal::Cylinder::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:630
coal::ConvexBase::Neighbors::operator[]
unsigned int & operator[](int i)
Definition: coal/shape/geometric_shapes.h:692
coal::Plane::operator=
Plane & operator=(const Plane &other)
operator =
Definition: coal/shape/geometric_shapes.h:1001
coal::Ellipsoid::Ellipsoid
Ellipsoid()
Default constructor.
Definition: coal/shape/geometric_shapes.h:308
coal::Cone::computeCOM
Vec3s computeCOM() const
compute center of mass
Definition: coal/shape/geometric_shapes.h:508
coal::Capsule::Capsule
Capsule(const Capsule &other)
Definition: coal/shape/geometric_shapes.h:392
coal::Cylinder::Cylinder
Cylinder(CoalScalar radius_, CoalScalar lz_)
Definition: coal/shape/geometric_shapes.h:565
coal::Ellipsoid::Ellipsoid
Ellipsoid(const Vec3s &radii)
Definition: coal/shape/geometric_shapes.h:313
y
y
coal::Box::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:226
coal::Capsule::halfLength
CoalScalar halfLength
Half Length along z axis.
Definition: coal/shape/geometric_shapes.h:402
coal::GEOM_CONE
@ GEOM_CONE
Definition: coal/collision_object.h:77
coal::Plane::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:1044
coal::Halfspace
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
Definition: coal/shape/geometric_shapes.h:892
coal::GEOM_CONVEX
@ GEOM_CONVEX
Definition: coal/collision_object.h:79
coal::Halfspace::Halfspace
Halfspace()
Definition: coal/shape/geometric_shapes.h:905
coal::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: coal/collision_object.h:64
coal::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: coal/shape/geometric_shapes.h:383
coal::Cylinder::radius
CoalScalar radius
Radius of the cylinder.
Definition: coal/shape/geometric_shapes.h:581
coal::Box::Box
Box(const Box &other)
Definition: coal/shape/geometric_shapes.h:173
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::ConvexBase::ConvexBase
ConvexBase()
Construct an uninitialized convex object Initialization is done with ConvexBase::initialize.
Definition: coal/shape/geometric_shapes.h:762
coal::ConvexBase::Neighbors::operator!=
bool operator!=(const Neighbors &other) const
Definition: coal/shape/geometric_shapes.h:711
coal::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: coal/collision_object.h:76
coal::TriangleP::getNodeType
NODE_TYPE getNodeType() const
get the node type
Definition: coal/shape/geometric_shapes.h:126
coal::ShapeBase::getObjectType
OBJECT_TYPE getObjectType() const
Get object type: a geometric shape.
Definition: coal/shape/geometric_shapes.h:72
coal::Cone::Cone
Cone(CoalScalar radius_, CoalScalar lz_)
Definition: coal/shape/geometric_shapes.h:472
coal::Sphere::Sphere
Sphere(CoalScalar radius_)
Definition: coal/shape/geometric_shapes.h:245
coal::Cylinder::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/shape/geometric_shapes.h:595
coal::Ellipsoid
Ellipsoid centered at point zero.
Definition: coal/shape/geometric_shapes.h:305
coal::Plane::distance
CoalScalar distance(const Vec3s &p) const
Definition: coal/shape/geometric_shapes.h:1023
coal::GEOM_SPHERE
@ GEOM_SPHERE
Definition: coal/collision_object.h:75
collision_object.h
coal::ConvexBase::normals
std::shared_ptr< std::vector< Vec3s > > normals
An array of the normals of the polygon.
Definition: coal/shape/geometric_shapes.h:723
coal::Cone::getNodeType
NODE_TYPE getNodeType() const
Get node type: a cone.
Definition: coal/shape/geometric_shapes.h:492
coal::Ellipsoid::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:366
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::Sphere::Sphere
Sphere()
Default constructor.
Definition: coal/shape/geometric_shapes.h:243
coal::TriangleP::TriangleP
TriangleP(const TriangleP &other)
Definition: coal/shape/geometric_shapes.h:117
coal::Ellipsoid::radii
Vec3s radii
Radii of the Ellipsoid (such that on boundary: x^2/rx^2 + y^2/ry^2.
Definition: coal/shape/geometric_shapes.h:318
coal::Plane
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
Definition: coal/shape/geometric_shapes.h:983
coal::Cylinder::minInflationValue
CoalScalar minInflationValue() const
Definition: coal/shape/geometric_shapes.h:607
a
list a
coal::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
coal::Capsule::getNodeType
NODE_TYPE getNodeType() const
Get node type: a capsule.
Definition: coal/shape/geometric_shapes.h:408
coal::ConvexBase::Neighbors::count
unsigned char const & count() const
Definition: coal/shape/geometric_shapes.h:691
coal::Sphere
Center at zero point sphere.
Definition: coal/shape/geometric_shapes.h:240
coal::ConvexBase::Neighbors::count_
unsigned char count_
Definition: coal/shape/geometric_shapes.h:688
coal::TriangleP::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:152
coal::Box::minInflationValue
CoalScalar minInflationValue() const
Definition: coal/shape/geometric_shapes.h:205
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::Cone::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/shape/geometric_shapes.h:499
coal::Box::Box
Box(CoalScalar x, CoalScalar y, CoalScalar z)
Definition: coal/shape/geometric_shapes.h:168
coal::Ellipsoid::minInflationValue
CoalScalar minInflationValue() const
Definition: coal/shape/geometric_shapes.h:345
orgQhull::Qhull
Interface to Qhull from C++.
Definition: Qhull.h:49
coal::ConvexBase::Neighbors
Definition: coal/shape/geometric_shapes.h:687
coal::Halfspace::clone
virtual Halfspace * clone() const
Clone *this into a new Halfspace.
Definition: coal/shape/geometric_shapes.h:918
coal::Box::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/shape/geometric_shapes.h:199
coal::Capsule::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/shape/geometric_shapes.h:410
coal::ConvexBase::num_normals_and_offsets
unsigned int num_normals_and_offsets
Definition: coal/shape/geometric_shapes.h:727
coal::Plane::signedDistance
CoalScalar signedDistance(const Vec3s &p) const
Definition: coal/shape/geometric_shapes.h:1010
coal::Halfspace::distance
CoalScalar distance(const Vec3s &p) const
Definition: coal/shape/geometric_shapes.h:924
coal::GEOM_PLANE
@ GEOM_PLANE
Definition: coal/collision_object.h:80
coal::TriangleP::a
Vec3s a
Definition: coal/shape/geometric_shapes.h:149
coal::Box::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/shape/geometric_shapes.h:197
coal::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: coal/collision_object.h:84
d
d
coal::ConvexBase::SupportWarmStartPolytope
The support warm start polytope contains certain points of this which are support points in specific ...
Definition: coal/shape/geometric_shapes.h:742
coal::ShapeBase::ShapeBase
ShapeBase(const ShapeBase &other)
&#160;
Definition: coal/shape/geometric_shapes.h:63
c
c
coal::Capsule::Capsule
Capsule(CoalScalar radius_, CoalScalar lz_)
Definition: coal/shape/geometric_shapes.h:388
coal::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: coal/collision_object.h:81
coal::Sphere::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/shape/geometric_shapes.h:266
qh
#define qh
Definition: libqhull.h:457
coal::Halfspace::getNodeType
NODE_TYPE getNodeType() const
Get node type: a half space.
Definition: coal/shape/geometric_shapes.h:932
coal::Cone::halfLength
CoalScalar halfLength
Half Length along z axis.
Definition: coal/shape/geometric_shapes.h:486
coal::ShapeBase
Base class for all basic geometric shapes.
Definition: coal/shape/geometric_shapes.h:58
coal::Ellipsoid::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/shape/geometric_shapes.h:340
coal::Ellipsoid::getNodeType
NODE_TYPE getNodeType() const
Get node type: an ellipsoid.
Definition: coal/shape/geometric_shapes.h:328
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
coal::Halfspace::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:966
coal::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: coal/collision_object.h:82
coal::Sphere::getNodeType
NODE_TYPE getNodeType() const
Get node type: a sphere.
Definition: coal/shape/geometric_shapes.h:259
value
float value
x
x
coal::Halfspace::signedDistance
CoalScalar signedDistance(const Vec3s &p) const
Definition: coal/shape/geometric_shapes.h:920
coal::Box::Box
Box(const Vec3s &side_)
Definition: coal/shape/geometric_shapes.h:171
coal::Ellipsoid::Ellipsoid
Ellipsoid(CoalScalar rx, CoalScalar ry, CoalScalar rz)
Definition: coal/shape/geometric_shapes.h:310
coal::Cylinder
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition: coal/shape/geometric_shapes.h:560
coal::Plane::Plane
Plane(const Plane &other)
Definition: coal/shape/geometric_shapes.h:998
coal::Plane::Plane
Plane(CoalScalar a, CoalScalar b, CoalScalar c, CoalScalar d_)
Construct a plane with normal direction and offset.
Definition: coal/shape/geometric_shapes.h:991
coal::TriangleP::TriangleP
TriangleP()
Definition: coal/shape/geometric_shapes.h:112
coal::Cone::Cone
Cone()
Default constructor.
Definition: coal/shape/geometric_shapes.h:470
coal::ConvexBase::Neighbors::operator[]
unsigned int const & operator[](int i) const
Definition: coal/shape/geometric_shapes.h:696
coal::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: coal/collision_object.h:52
coal::OT_GEOM
@ OT_GEOM
Definition: coal/collision_object.h:55
coal::Capsule::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:451
coal::TriangleP::TriangleP
TriangleP(const Vec3s &a_, const Vec3s &b_, const Vec3s &c_)
Definition: coal/shape/geometric_shapes.h:114
coal::Capsule::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/shape/geometric_shapes.h:415
coal::TriangleP
Triangle stores the points instead of only indices of points.
Definition: coal/shape/geometric_shapes.h:110
coal::Halfspace::operator=
Halfspace & operator=(const Halfspace &other)
operator =
Definition: coal/shape/geometric_shapes.h:911
coal::ConvexBase::center
Vec3s center
center of the convex polytope, this is used for collision: center is guaranteed in the internal of th...
Definition: coal/shape/geometric_shapes.h:736
coal::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: coal/collision_object.h:78
coal::ShapeBase::getSweptSphereRadius
CoalScalar getSweptSphereRadius() const
Get radius of sphere swept around the shape. This radius is always >= 0.
Definition: coal/shape/geometric_shapes.h:86
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::Cone
Cone The base of the cone is at and the top is at .
Definition: coal/shape/geometric_shapes.h:467
coal::Plane::clone
virtual Plane * clone() const
Clone *this into a new Plane.
Definition: coal/shape/geometric_shapes.h:1008
coal::ConvexBase::SupportWarmStartPolytope::points
std::vector< Vec3s > points
Array of support points to warm start the support function computation.
Definition: coal/shape/geometric_shapes.h:745
coal::Box::halfSide
Vec3s halfSide
box side half-length
Definition: coal/shape/geometric_shapes.h:189
coal::Sphere::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/shape/geometric_shapes.h:261
coal::Halfspace::n
Vec3s n
Plane normal.
Definition: coal/shape/geometric_shapes.h:956
coal::ShapeBase::ShapeBase
ShapeBase()
Definition: coal/shape/geometric_shapes.h:60
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::Sphere::radius
CoalScalar radius
Radius of the sphere.
Definition: coal/shape/geometric_shapes.h:250
coal::Plane::getNodeType
NODE_TYPE getNodeType() const
Get node type: a plane.
Definition: coal/shape/geometric_shapes.h:1031
coal::Cone::radius
CoalScalar radius
Radius of the cone.
Definition: coal/shape/geometric_shapes.h:480
coal::Capsule::Capsule
Capsule()
Default constructor.
Definition: coal/shape/geometric_shapes.h:386
coal::ConvexBase::offsets
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.
Definition: coal/shape/geometric_shapes.h:726
coal::Halfspace::d
CoalScalar d
Plane offset.
Definition: coal/shape/geometric_shapes.h:959
coal::Plane::n
Vec3s n
Plane normal.
Definition: coal/shape/geometric_shapes.h:1034
r2
r2
coal::Plane::Plane
Plane(const Vec3s &n_, CoalScalar d_)
Construct a plane with normal direction and offset.
Definition: coal/shape/geometric_shapes.h:986
coal::ShapeBase::setSweptSphereRadius
void setSweptSphereRadius(CoalScalar radius)
Set radius of sphere swept around the shape. Must be >= 0.
Definition: coal/shape/geometric_shapes.h:76
coal::Capsule::radius
CoalScalar radius
Radius of capsule.
Definition: coal/shape/geometric_shapes.h:396
coal::Halfspace::Halfspace
Halfspace(const Halfspace &other)
Definition: coal/shape/geometric_shapes.h:907
coal::Cylinder::Cylinder
Cylinder(const Cylinder &other)
Definition: coal/shape/geometric_shapes.h:569
coal::Cone::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:545
coal::ConvexBase::SupportWarmStartPolytope::indices
std::vector< int > indices
Indices of the support points warm starts. These are the indices of the real convex,...
Definition: coal/shape/geometric_shapes.h:750
coal::TriangleP::c
Vec3s c
Definition: coal/shape/geometric_shapes.h:149
coal::Sphere::Sphere
Sphere(const Sphere &other)
Definition: coal/shape/geometric_shapes.h:247
coal::Halfspace::Halfspace
Halfspace(CoalScalar a, CoalScalar b, CoalScalar c, CoalScalar d_)
Construct a plane with normal direction and offset.
Definition: coal/shape/geometric_shapes.h:900
coal::Cone::minInflationValue
CoalScalar minInflationValue() const
Definition: coal/shape/geometric_shapes.h:510
coal::Cone::Cone
Cone(const Cone &other)
Definition: coal/shape/geometric_shapes.h:476
coal::Cylinder::Cylinder
Cylinder()
Default constructor.
Definition: coal/shape/geometric_shapes.h:563
coal::Sphere::minInflationValue
CoalScalar minInflationValue() const
Definition: coal/shape/geometric_shapes.h:271
c2
c2
coal::Halfspace::minInflationValue
CoalScalar minInflationValue() const
Definition: coal/shape/geometric_shapes.h:934
coal::GEOM_BOX
@ GEOM_BOX
Definition: coal/collision_object.h:74
coal::ConvexBase::nneighbors_
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...
Definition: coal/shape/geometric_shapes.h:801
coal::Halfspace::Halfspace
Halfspace(const Vec3s &n_, CoalScalar d_)
Construct a half space with normal direction and offset.
Definition: coal/shape/geometric_shapes.h:895
coal::Ellipsoid::inflated
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...
Definition: coal/shape/geometric_shapes.h:355
coal::ConvexBase::support_warm_starts
SupportWarmStartPolytope support_warm_starts
Support warm start polytopes.
Definition: coal/shape/geometric_shapes.h:757
coal::ConvexBase::points
std::shared_ptr< std::vector< Vec3s > > points
An array of the points of the polygon.
Definition: coal/shape/geometric_shapes.h:719
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::ShapeBase::~ShapeBase
virtual ~ShapeBase()
Definition: coal/shape/geometric_shapes.h:69
coal::Box::Box
Box()
Default constructor.
Definition: coal/shape/geometric_shapes.h:186
coal::Capsule::inflated
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...
Definition: coal/shape/geometric_shapes.h:440
coal::Plane::Plane
Plane()
Definition: coal/shape/geometric_shapes.h:996
coal::ConvexBase::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/shape/geometric_shapes.h:806
coal::Plane::d
CoalScalar d
Plane offset.
Definition: coal/shape/geometric_shapes.h:1037
coal::Ellipsoid::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/shape/geometric_shapes.h:330
initialize
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.
Definition: coal/internal/traversal_node_setup.h:467
coal::Box::inflated
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 >...
Definition: coal/shape/geometric_shapes.h:215
coal::Cylinder::operator=
Cylinder & operator=(const Cylinder &other)
Definition: coal/shape/geometric_shapes.h:572
coal::ConvexBase
Base for convex polytope.
Definition: coal/shape/geometric_shapes.h:645


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:58