coal/collision_data.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  * Copyright (c) 2024, INRIA
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Open Source Robotics Foundation nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  */
36 
39 #ifndef COAL_COLLISION_DATA_H
40 #define COAL_COLLISION_DATA_H
41 
42 #include <vector>
43 #include <array>
44 #include <set>
45 #include <limits>
46 #include <numeric>
47 
48 #include "coal/collision_object.h"
49 #include "coal/config.hh"
50 #include "coal/data_types.h"
51 #include "coal/timings.h"
53 #include "coal/logging.h"
54 
55 namespace coal {
56 
58 struct COAL_DLLAPI Contact {
61 
64 
69  int b1;
70 
75  int b2;
76 
89 
99  std::array<Vec3s, 2> nearest_points;
100 
103 
106 
108  static const int NONE = -1;
109 
111  Contact() : o1(NULL), o2(NULL), b1(NONE), b2(NONE) {
112  penetration_depth = (std::numeric_limits<CoalScalar>::max)();
113  nearest_points[0] = nearest_points[1] = normal = pos =
114  Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN());
115  }
116 
117  Contact(const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_,
118  int b2_)
119  : o1(o1_), o2(o2_), b1(b1_), b2(b2_) {
120  penetration_depth = (std::numeric_limits<CoalScalar>::max)();
121  nearest_points[0] = nearest_points[1] = normal = pos =
122  Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN());
123  }
124 
125  Contact(const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_,
126  int b2_, const Vec3s& pos_, const Vec3s& normal_, CoalScalar depth_)
127  : o1(o1_),
128  o2(o2_),
129  b1(b1_),
130  b2(b2_),
131  normal(normal_),
132  nearest_points{pos_ - (depth_ * normal_ / 2),
133  pos_ + (depth_ * normal_ / 2)},
134  pos(pos_),
135  penetration_depth(depth_) {}
136 
137  Contact(const CollisionGeometry* o1_, const CollisionGeometry* o2_, int b1_,
138  int b2_, const Vec3s& p1, const Vec3s& p2, const Vec3s& normal_,
139  CoalScalar depth_)
140  : o1(o1_),
141  o2(o2_),
142  b1(b1_),
143  b2(b2_),
144  normal(normal_),
145  nearest_points{p1, p2},
146  pos((p1 + p2) / 2),
147  penetration_depth(depth_) {}
148 
149  bool operator<(const Contact& other) const {
150  if (b1 == other.b1) return b2 < other.b2;
151  return b1 < other.b1;
152  }
153 
154  bool operator==(const Contact& other) const {
155  return o1 == other.o1 && o2 == other.o2 && b1 == other.b1 &&
156  b2 == other.b2 && normal == other.normal && pos == other.pos &&
157  nearest_points[0] == other.nearest_points[0] &&
158  nearest_points[1] == other.nearest_points[1] &&
159  penetration_depth == other.penetration_depth;
160  }
161 
162  bool operator!=(const Contact& other) const { return !(*this == other); }
163 
164  CoalScalar getDistanceToCollision(const CollisionRequest& request) const;
165 };
166 
167 struct QueryResult;
168 
170 struct COAL_DLLAPI QueryRequest {
171  // @brief Initial guess to use for the GJK algorithm
173 
176  COAL_DEPRECATED_MESSAGE(Use gjk_initial_guess instead)
177  bool enable_cached_gjk_guess;
178 
180  mutable Vec3s cached_gjk_guess;
181 
183  mutable support_func_guess_t cached_support_func_guess;
184 
186  size_t gjk_max_iterations;
187 
192  CoalScalar gjk_tolerance;
193 
195  GJKVariant gjk_variant;
196 
198  GJKConvergenceCriterion gjk_convergence_criterion;
199 
201  GJKConvergenceCriterionType gjk_convergence_criterion_type;
202 
204  size_t epa_max_iterations;
205 
211  CoalScalar epa_tolerance;
212 
214  bool enable_timings;
215 
217  CoalScalar collision_distance_threshold;
218 
223  : gjk_initial_guess(GJKInitialGuess::DefaultGuess),
224  enable_cached_gjk_guess(false),
225  cached_gjk_guess(1, 0, 0),
226  cached_support_func_guess(support_func_guess_t::Zero()),
227  gjk_max_iterations(GJK_DEFAULT_MAX_ITERATIONS),
228  gjk_tolerance(GJK_DEFAULT_TOLERANCE),
229  gjk_variant(GJKVariant::DefaultGJK),
230  gjk_convergence_criterion(GJKConvergenceCriterion::Default),
231  gjk_convergence_criterion_type(GJKConvergenceCriterionType::Relative),
232  epa_max_iterations(EPA_DEFAULT_MAX_ITERATIONS),
233  epa_tolerance(EPA_DEFAULT_TOLERANCE),
234  enable_timings(false),
235  collision_distance_threshold(
236  Eigen::NumTraits<CoalScalar>::dummy_precision()) {}
237 
239  QueryRequest(const QueryRequest& other) = default;
240 
242  QueryRequest& operator=(const QueryRequest& other) = default;
244 
250  void updateGuess(const QueryResult& result) const;
251 
253  inline bool operator==(const QueryRequest& other) const {
256  return gjk_initial_guess == other.gjk_initial_guess &&
257  enable_cached_gjk_guess == other.enable_cached_gjk_guess &&
258  gjk_variant == other.gjk_variant &&
259  gjk_convergence_criterion == other.gjk_convergence_criterion &&
260  gjk_convergence_criterion_type ==
262  gjk_tolerance == other.gjk_tolerance &&
263  gjk_max_iterations == other.gjk_max_iterations &&
264  cached_gjk_guess == other.cached_gjk_guess &&
265  cached_support_func_guess == other.cached_support_func_guess &&
266  epa_max_iterations == other.epa_max_iterations &&
267  epa_tolerance == other.epa_tolerance &&
268  enable_timings == other.enable_timings &&
269  collision_distance_threshold == other.collision_distance_threshold;
271  }
272 };
273 
275 struct COAL_DLLAPI QueryResult {
278 
281 
284 
286  : cached_gjk_guess(Vec3s::Zero()),
287  cached_support_func_guess(support_func_guess_t::Constant(-1)) {}
288 };
289 
290 inline void QueryRequest::updateGuess(const QueryResult& result) const {
297  }
299 }
300 
301 struct CollisionResult;
302 
305  CONTACT = 0x00001,
307  NO_REQUEST = 0x01000
308 };
309 
311 struct COAL_DLLAPI CollisionRequest : QueryRequest {
314 
318 
320  COAL_DEPRECATED_MESSAGE(A lower bound on distance is always computed.)
321  bool enable_distance_lower_bound;
322 
328  CoalScalar security_margin;
329 
332  CoalScalar break_distance;
333 
340  CoalScalar distance_upper_bound;
341 
349  CollisionRequest(const CollisionRequestFlag flag, size_t num_max_contacts_)
350  : num_max_contacts(num_max_contacts_),
351  enable_contact(flag & CONTACT),
352  enable_distance_lower_bound(flag & DISTANCE_LOWER_BOUND),
353  security_margin(0),
354  break_distance(1e-3),
355  distance_upper_bound((std::numeric_limits<CoalScalar>::max)()) {}
356 
359  : num_max_contacts(1),
360  enable_contact(true),
361  enable_distance_lower_bound(false),
362  security_margin(0),
363  break_distance(1e-3),
364  distance_upper_bound((std::numeric_limits<CoalScalar>::max)()) {}
366 
367  bool isSatisfied(const CollisionResult& result) const;
368 
370  inline bool operator==(const CollisionRequest& other) const {
373  return QueryRequest::operator==(other) &&
375  enable_contact == other.enable_contact &&
376  enable_distance_lower_bound == other.enable_distance_lower_bound &&
377  security_margin == other.security_margin &&
378  break_distance == other.break_distance &&
379  distance_upper_bound == other.distance_upper_bound;
381  }
382 };
383 
385  const CollisionRequest& request) const {
386  return penetration_depth - request.security_margin;
387 }
388 
390 struct COAL_DLLAPI CollisionResult : QueryResult {
391  private:
393  std::vector<Contact> contacts;
394 
395  public:
402 
406 
414  std::array<Vec3s, 2> nearest_points;
415 
416  public:
418  : distance_lower_bound((std::numeric_limits<CoalScalar>::max)()) {
419  nearest_points[0] = nearest_points[1] = normal =
420  Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN());
421  }
422 
425  const CoalScalar& distance_lower_bound_) {
426  if (distance_lower_bound_ < distance_lower_bound)
427  distance_lower_bound = distance_lower_bound_;
428  }
429 
431  inline void addContact(const Contact& c) { contacts.push_back(c); }
432 
434  inline bool operator==(const CollisionResult& other) const {
435  return contacts == other.contacts &&
437  nearest_points[0] == other.nearest_points[0] &&
438  nearest_points[1] == other.nearest_points[1] &&
439  normal == other.normal;
440  }
441 
443  bool isCollision() const { return contacts.size() > 0; }
444 
446  size_t numContacts() const { return contacts.size(); }
447 
449  const Contact& getContact(size_t i) const {
450  if (contacts.size() == 0)
452  "The number of contacts is zero. No Contact can be returned.",
453  std::invalid_argument);
454 
455  if (i < contacts.size())
456  return contacts[i];
457  else
458  return contacts.back();
459  }
460 
462  void setContact(size_t i, const Contact& c) {
463  if (contacts.size() == 0)
465  "The number of contacts is zero. No Contact can be returned.",
466  std::invalid_argument);
467 
468  if (i < contacts.size())
469  contacts[i] = c;
470  else
471  contacts.back() = c;
472  }
473 
475  void getContacts(std::vector<Contact>& contacts_) const {
476  contacts_.resize(contacts.size());
477  std::copy(contacts.begin(), contacts.end(), contacts_.begin());
478  }
479 
480  const std::vector<Contact>& getContacts() const { return contacts; }
481 
483  void clear() {
484  distance_lower_bound = (std::numeric_limits<CoalScalar>::max)();
485  contacts.clear();
486  timings.clear();
487  nearest_points[0] = nearest_points[1] = normal =
488  Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN());
489  }
490 
493  void swapObjects();
494 };
495 
512 struct COAL_DLLAPI ContactPatch {
513  public:
514  using Polygon = std::vector<Vec2s>;
515 
519 
529  enum PatchDirection { DEFAULT = 0, INVERTED = 1 };
530 
533 
546 
549  static constexpr size_t default_preallocated_size = 12;
550 
551  protected:
554 
555  public:
561  explicit ContactPatch(size_t preallocated_size = default_preallocated_size)
562  : tf(Transform3s::Identity()),
563  direction(PatchDirection::DEFAULT),
564  penetration_depth(0) {
565  this->m_points.reserve(preallocated_size);
566  }
567 
569  Vec3s getNormal() const {
570  if (this->direction == PatchDirection::INVERTED) {
571  return -this->tf.rotation().col(2);
572  }
573  return this->tf.rotation().col(2);
574  }
575 
577  size_t size() const { return this->m_points.size(); }
578 
584  void addPoint(const Vec3s& point_3d) {
585  const Vec3s point = this->tf.inverseTransform(point_3d);
586  this->m_points.emplace_back(point.template head<2>());
587  }
588 
590  Vec3s getPoint(const size_t i) const {
591  Vec3s point(0, 0, 0);
592  point.head<2>() = this->point(i);
593  point = tf.transform(point);
594  return point;
595  }
596 
600  Vec3s getPointShape1(const size_t i) const {
601  Vec3s point = this->getPoint(i);
602  point -= (this->penetration_depth / 2) * this->getNormal();
603  return point;
604  }
605 
609  Vec3s getPointShape2(const size_t i) const {
610  Vec3s point = this->getPoint(i);
611  point += (this->penetration_depth / 2) * this->getNormal();
612  return point;
613  }
614 
616  Polygon& points() { return this->m_points; }
617 
619  const Polygon& points() const { return this->m_points; }
620 
622  Vec2s& point(const size_t i) {
623  COAL_ASSERT(this->m_points.size() > 0, "Patch is empty.", std::logic_error);
624  if (i < this->m_points.size()) {
625  return this->m_points[i];
626  }
627  return this->m_points.back();
628  }
629 
631  const Vec2s& point(const size_t i) const {
632  COAL_ASSERT(this->m_points.size() > 0, "Patch is empty.", std::logic_error);
633  if (i < this->m_points.size()) {
634  return this->m_points[i];
635  }
636  return this->m_points.back();
637  }
638 
640  void clear() {
641  this->m_points.clear();
642  this->tf.setIdentity();
643  this->penetration_depth = 0;
644  }
645 
650  bool operator==(const ContactPatch& other) const {
651  return this->tf == other.tf && this->direction == other.direction &&
652  this->penetration_depth == other.penetration_depth &&
653  this->points() == other.points();
654  }
655 
658  bool isSame(const ContactPatch& other,
659  const CoalScalar tol =
660  Eigen::NumTraits<CoalScalar>::dummy_precision()) const {
661  // The x and y axis of the set are arbitrary, but the z axis is
662  // always the normal. The position of the origin of the frame is also
663  // arbitrary. So we only check if the normals are the same.
664  if (!this->getNormal().isApprox(other.getNormal(), tol)) {
665  return false;
666  }
667 
668  if (std::abs(this->penetration_depth - other.penetration_depth) > tol) {
669  return false;
670  }
671 
672  if (this->direction != other.direction) {
673  return false;
674  }
675 
676  if (this->size() != other.size()) {
677  return false;
678  }
679 
680  // Check all points of the contact patch.
681  for (size_t i = 0; i < this->size(); ++i) {
682  bool found = false;
683  const Vec3s pi = this->getPoint(i);
684  for (size_t j = 0; j < other.size(); ++j) {
685  const Vec3s other_pj = other.getPoint(j);
686  if (pi.isApprox(other_pj, tol)) {
687  found = true;
688  }
689  }
690  if (!found) {
691  return false;
692  }
693  }
694 
695  return true;
696  }
697 };
698 
705  ContactPatch& contact_patch) {
706  contact_patch.penetration_depth = contact.penetration_depth;
707  contact_patch.tf.translation() = contact.pos;
708  contact_patch.tf.rotation() =
710  contact_patch.direction = ContactPatch::PatchDirection::DEFAULT;
711 }
712 
722 
724 struct COAL_DLLAPI ContactPatchRequest {
727 
728  protected:
734 
745 
746  public:
761  explicit ContactPatchRequest(size_t max_num_patch = 1,
762  size_t num_samples_curved_shapes =
764  CoalScalar patch_tolerance = 1e-3)
765  : max_num_patch(max_num_patch) {
766  this->setNumSamplesCurvedShapes(num_samples_curved_shapes);
767  this->setPatchTolerance(patch_tolerance);
768  }
769 
771  explicit ContactPatchRequest(const CollisionRequest& collision_request,
772  size_t num_samples_curved_shapes =
774  CoalScalar patch_tolerance = 1e-3)
775  : max_num_patch(collision_request.num_max_contacts) {
776  this->setNumSamplesCurvedShapes(num_samples_curved_shapes);
777  this->setPatchTolerance(patch_tolerance);
778  }
779 
781  void setNumSamplesCurvedShapes(const size_t num_samples_curved_shapes) {
782  if (num_samples_curved_shapes < 3) {
784  "`num_samples_curved_shapes` cannot be lower than 3. Setting it to "
785  "3 to prevent bugs.");
786  this->m_num_samples_curved_shapes = 3;
787  } else {
788  this->m_num_samples_curved_shapes = num_samples_curved_shapes;
789  }
790  }
791 
793  size_t getNumSamplesCurvedShapes() const {
794  return this->m_num_samples_curved_shapes;
795  }
796 
798  void setPatchTolerance(const CoalScalar patch_tolerance) {
799  if (patch_tolerance < 0) {
801  "`patch_tolerance` cannot be negative. Setting it to 0 to prevent "
802  "bugs.");
803  this->m_patch_tolerance = Eigen::NumTraits<CoalScalar>::dummy_precision();
804  } else {
805  this->m_patch_tolerance = patch_tolerance;
806  }
807  }
808 
810  CoalScalar getPatchTolerance() const { return this->m_patch_tolerance; }
811 
813  bool operator==(const ContactPatchRequest& other) const {
814  return this->max_num_patch == other.max_num_patch &&
815  this->getNumSamplesCurvedShapes() ==
816  other.getNumSamplesCurvedShapes() &&
817  this->getPatchTolerance() == other.getPatchTolerance();
818  }
819 };
820 
822 struct COAL_DLLAPI ContactPatchResult {
823  using ContactPatchVector = std::vector<ContactPatch>;
824  using ContactPatchRef = std::reference_wrapper<ContactPatch>;
825  using ContactPatchRefVector = std::vector<ContactPatchRef>;
826 
827  protected:
835 
840 
843 
844  public:
846  ContactPatchResult() : m_id_available_patch(0) {
847  const size_t max_num_patch = 1;
848  const ContactPatchRequest request(max_num_patch);
849  this->set(request);
850  }
851 
853  explicit ContactPatchResult(const ContactPatchRequest& request)
854  : m_id_available_patch(0) {
855  this->set(request);
856  };
857 
859  size_t numContactPatches() const { return this->m_contact_patches.size(); }
860 
863  if (this->m_id_available_patch >= this->m_contact_patches_data.size()) {
865  "Trying to get an unused contact patch but all contact patches are "
866  "used. Increasing size of contact patches vector, at the cost of a "
867  "copy. You should increase `max_num_patch` in the "
868  "`ContactPatchRequest`.");
869  this->m_contact_patches_data.emplace_back(
870  this->m_contact_patches_data.back());
871  this->m_contact_patches_data.back().clear();
872  }
873  ContactPatch& contact_patch =
874  this->m_contact_patches_data[this->m_id_available_patch];
875  contact_patch.clear();
876  this->m_contact_patches.emplace_back(contact_patch);
877  ++(this->m_id_available_patch);
878  return this->m_contact_patches.back();
879  }
880 
882  const ContactPatch& getContactPatch(const size_t i) const {
883  if (this->m_contact_patches.empty()) {
885  "The number of contact patches is zero. No ContactPatch can be "
886  "returned.",
887  std::invalid_argument);
888  }
889  if (i < this->m_contact_patches.size()) {
890  return this->m_contact_patches[i];
891  }
892  return this->m_contact_patches.back();
893  }
894 
896  ContactPatch& contactPatch(const size_t i) {
897  if (this->m_contact_patches.empty()) {
899  "The number of contact patches is zero. No ContactPatch can be "
900  "returned.",
901  std::invalid_argument);
902  }
903  if (i < this->m_contact_patches.size()) {
904  return this->m_contact_patches[i];
905  }
906  return this->m_contact_patches.back();
907  }
908 
910  void clear() {
911  this->m_contact_patches.clear();
912  this->m_id_available_patch = 0;
913  for (ContactPatch& patch : this->m_contact_patches_data) {
914  patch.clear();
915  }
916  }
917 
919  void set(const ContactPatchRequest& request) {
920  if (this->m_contact_patches_data.size() < request.max_num_patch) {
921  this->m_contact_patches_data.resize(request.max_num_patch);
922  }
923  for (ContactPatch& patch : this->m_contact_patches_data) {
924  patch.points().reserve(request.getNumSamplesCurvedShapes());
925  }
926  this->clear();
927  }
928 
931  bool check(const ContactPatchRequest& request) const {
932  assert(this->m_contact_patches_data.size() >= request.max_num_patch);
933  if (this->m_contact_patches_data.size() < request.max_num_patch) {
934  return false;
935  }
936 
937  for (const ContactPatch& patch : this->m_contact_patches_data) {
938  if (patch.points().capacity() < request.getNumSamplesCurvedShapes()) {
939  assert(patch.points().capacity() >=
940  request.getNumSamplesCurvedShapes());
941  return false;
942  }
943  }
944  return true;
945  }
946 
948  bool operator==(const ContactPatchResult& other) const {
949  if (this->numContactPatches() != other.numContactPatches()) {
950  return false;
951  }
952 
953  for (size_t i = 0; i < this->numContactPatches(); ++i) {
954  const ContactPatch& patch = this->getContactPatch(i);
955  const ContactPatch& other_patch = other.getContactPatch(i);
956  if (!(patch == other_patch)) {
957  return false;
958  }
959  }
960 
961  return true;
962  }
963 
966  void swapObjects() {
967  // Create new transform: it's the reflection of `tf` along the z-axis.
968  // This corresponds to doing a PI rotation along the y-axis, i.e. the x-axis
969  // becomes -x-axis, y-axis stays the same, z-axis becomes -z-axis.
970  for (size_t i = 0; i < this->numContactPatches(); ++i) {
971  ContactPatch& patch = this->contactPatch(i);
972  patch.tf.rotation().col(0) *= -1.0;
973  patch.tf.rotation().col(2) *= -1.0;
974 
975  for (size_t j = 0; j < patch.size(); ++j) {
976  patch.point(i)(0) *= -1.0; // only invert the x-axis
977  }
978  }
979  }
980 };
981 
982 struct DistanceResult;
983 
985 struct COAL_DLLAPI DistanceRequest : QueryRequest {
989  COAL_DEPRECATED_MESSAGE(
990  Nearest points are always computed : they are the points of the shapes
991  that achieve a distance of
993  .\n Use `enable_signed_distance` if you want to compute a signed
994  minimum distance(and thus its corresponding nearest points)
995  .)
996  bool enable_nearest_points;
997 
1011 
1013  CoalScalar rel_err; // relative error, between 0 and 1
1014  CoalScalar abs_err; // absolute error
1015 
1022  DistanceRequest(bool enable_nearest_points_ = true,
1023  bool enable_signed_distance_ = true,
1024  CoalScalar rel_err_ = 0.0, CoalScalar abs_err_ = 0.0)
1025  : enable_nearest_points(enable_nearest_points_),
1026  enable_signed_distance(enable_signed_distance_),
1027  rel_err(rel_err_),
1028  abs_err(abs_err_) {}
1030 
1031  bool isSatisfied(const DistanceResult& result) const;
1032 
1035  DistanceRequest& operator=(const DistanceRequest& other) = default;
1037 
1039  inline bool operator==(const DistanceRequest& other) const {
1042  return QueryRequest::operator==(other) &&
1043  enable_nearest_points == other.enable_nearest_points &&
1044  enable_signed_distance == other.enable_signed_distance &&
1045  rel_err == other.rel_err && abs_err == other.abs_err;
1047  }
1048 };
1049 
1051 struct COAL_DLLAPI DistanceResult : QueryResult {
1052  public:
1059 
1062 
1065  std::array<Vec3s, 2> nearest_points;
1066 
1069 
1072 
1077  int b1;
1078 
1083  int b2;
1084 
1086  static const int NONE = -1;
1087 
1089  CoalScalar min_distance_ = (std::numeric_limits<CoalScalar>::max)())
1090  : min_distance(min_distance_), o1(NULL), o2(NULL), b1(NONE), b2(NONE) {
1091  const Vec3s nan(
1092  Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN()));
1093  nearest_points[0] = nearest_points[1] = normal = nan;
1094  }
1095 
1098  const CollisionGeometry* o2_, int b1_, int b2_) {
1099  if (min_distance > distance) {
1100  min_distance = distance;
1101  o1 = o1_;
1102  o2 = o2_;
1103  b1 = b1_;
1104  b2 = b2_;
1105  }
1106  }
1107 
1110  const CollisionGeometry* o2_, int b1_, int b2_, const Vec3s& p1,
1111  const Vec3s& p2, const Vec3s& normal_) {
1112  if (min_distance > distance) {
1113  min_distance = distance;
1114  o1 = o1_;
1115  o2 = o2_;
1116  b1 = b1_;
1117  b2 = b2_;
1118  nearest_points[0] = p1;
1119  nearest_points[1] = p2;
1120  normal = normal_;
1121  }
1122  }
1123 
1125  void update(const DistanceResult& other_result) {
1126  if (min_distance > other_result.min_distance) {
1127  min_distance = other_result.min_distance;
1128  o1 = other_result.o1;
1129  o2 = other_result.o2;
1130  b1 = other_result.b1;
1131  b2 = other_result.b2;
1132  nearest_points[0] = other_result.nearest_points[0];
1133  nearest_points[1] = other_result.nearest_points[1];
1134  normal = other_result.normal;
1135  }
1136  }
1137 
1139  void clear() {
1140  const Vec3s nan(
1141  Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN()));
1142  min_distance = (std::numeric_limits<CoalScalar>::max)();
1143  o1 = NULL;
1144  o2 = NULL;
1145  b1 = NONE;
1146  b2 = NONE;
1147  nearest_points[0] = nearest_points[1] = normal = nan;
1148  timings.clear();
1149  }
1150 
1152  inline bool operator==(const DistanceResult& other) const {
1153  bool is_same = min_distance == other.min_distance &&
1154  nearest_points[0] == other.nearest_points[0] &&
1155  nearest_points[1] == other.nearest_points[1] &&
1156  normal == other.normal && o1 == other.o1 && o2 == other.o2 &&
1157  b1 == other.b1 && b2 == other.b2;
1158 
1159  // TODO: check also that two GeometryObject are indeed equal.
1160  if ((o1 != NULL) ^ (other.o1 != NULL)) return false;
1161  is_same &= (o1 == other.o1);
1162  // else if (o1 != NULL and other.o1 != NULL) is_same &= *o1 ==
1163  // *other.o1;
1164 
1165  if ((o2 != NULL) ^ (other.o2 != NULL)) return false;
1166  is_same &= (o2 == other.o2);
1167  // else if (o2 != NULL and other.o2 != NULL) is_same &= *o2 ==
1168  // *other.o2;
1169 
1170  return is_same;
1171  }
1172 };
1173 
1174 namespace internal {
1176  CollisionResult& res,
1177  const CoalScalar sqrDistLowerBound) {
1178  // BV cannot find negative distance.
1179  if (res.distance_lower_bound <= 0) return;
1180  CoalScalar new_dlb = std::sqrt(sqrDistLowerBound); // - req.security_margin;
1181  if (new_dlb < res.distance_lower_bound) res.distance_lower_bound = new_dlb;
1182 }
1183 
1185  CollisionResult& res,
1186  const CoalScalar& distance,
1187  const Vec3s& p0, const Vec3s& p1,
1188  const Vec3s& normal) {
1189  if (distance < res.distance_lower_bound) {
1190  res.distance_lower_bound = distance;
1191  res.nearest_points[0] = p0;
1192  res.nearest_points[1] = p1;
1193  res.normal = normal;
1194  }
1195 }
1196 } // namespace internal
1197 
1199  return static_cast<CollisionRequestFlag>(~static_cast<int>(a));
1200 }
1201 
1204  return static_cast<CollisionRequestFlag>(static_cast<int>(a) |
1205  static_cast<int>(b));
1206 }
1207 
1210  return static_cast<CollisionRequestFlag>(static_cast<int>(a) &
1211  static_cast<int>(b));
1212 }
1213 
1216  return static_cast<CollisionRequestFlag>(static_cast<int>(a) ^
1217  static_cast<int>(b));
1218 }
1219 
1222  return (CollisionRequestFlag&)((int&)(a) |= static_cast<int>(b));
1223 }
1224 
1227  return (CollisionRequestFlag&)((int&)(a) &= static_cast<int>(b));
1228 }
1229 
1232  return (CollisionRequestFlag&)((int&)(a) ^= static_cast<int>(b));
1233 }
1234 
1235 } // namespace coal
1236 
1237 #endif
coal::Contact::pos
Vec3s pos
contact position, in world space
Definition: coal/collision_data.h:102
coal::ContactPatch::penetration_depth
CoalScalar penetration_depth
Penetration depth of the contact patch. This value corresponds to the signed distance d between the s...
Definition: coal/collision_data.h:545
coal::QueryResult::cached_support_func_guess
support_func_guess_t cached_support_func_guess
stores the last support function vertex index, when relevant.
Definition: coal/collision_data.h:280
coal::GJKConvergenceCriterion
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)....
Definition: coal/data_types.h:104
coal::ContactPatch::Polygon
std::vector< Vec2s > Polygon
Definition: coal/collision_data.h:514
coal::QueryRequest::gjk_convergence_criterion
GJKConvergenceCriterion gjk_convergence_criterion
convergence criterion used to stop GJK
Definition: coal/collision_data.h:198
coal::ContactPatch::default_preallocated_size
static constexpr size_t default_preallocated_size
Default maximum size of the polygon representing the contact patch. Used to pre-allocate memory for t...
Definition: coal/collision_data.h:549
coal::CONTACT
@ CONTACT
Definition: coal/collision_data.h:305
coal::DistanceResult::o1
const CollisionGeometry * o1
collision object 1
Definition: coal/collision_data.h:1068
coal::QueryResult::QueryResult
QueryResult()
Definition: coal/collision_data.h:285
Eigen
coal::QueryRequest::gjk_tolerance
CoalScalar gjk_tolerance
tolerance for the GJK algorithm. Note: This tolerance determines the precision on the estimated dista...
Definition: coal/collision_data.h:192
coal::Contact::Contact
Contact(const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_, const Vec3s &p1, const Vec3s &p2, const Vec3s &normal_, CoalScalar depth_)
Definition: coal/collision_data.h:137
coal::ContactPatch::getPointShape2
Vec3s getPointShape2(const size_t i) const
Get the i-th point of the contact patch, projected back onto the first shape of the collision pair....
Definition: coal/collision_data.h:609
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::QueryRequest::gjk_initial_guess
GJKInitialGuess gjk_initial_guess
Definition: coal/collision_data.h:172
coal::ContactPatch::getPoint
Vec3s getPoint(const size_t i) const
Get the i-th point of the set, expressed in the 3D world frame.
Definition: coal/collision_data.h:590
coal::DistanceResult::update
void update(const DistanceResult &other_result)
add distance information into the result
Definition: coal/collision_data.h:1125
coal::QueryRequest::epa_tolerance
CoalScalar epa_tolerance
tolerance for EPA. Note: This tolerance determines the precision on the estimated distance between tw...
Definition: coal/collision_data.h:211
coal::CollisionRequest::enable_contact
bool enable_contact
whether the contact information (normal, penetration depth and contact position) will return.
Definition: coal/collision_data.h:317
coal::ContactPatch::operator==
bool operator==(const ContactPatch &other) const
Whether two contact patches are the same or not.
Definition: coal/collision_data.h:650
coal::QueryRequest::updateGuess
COAL_COMPILER_DIAGNOSTIC_POP void updateGuess(const QueryResult &result) const
Updates the guess for the internal GJK algorithm in order to warm-start it when reusing this collisio...
Definition: coal/collision_data.h:290
coal::CPUTimes
Definition: coal/timings.h:16
coal::Contact::Contact
Contact()
Default constructor.
Definition: coal/collision_data.h:111
coal::QueryRequest::cached_support_func_guess
support_func_guess_t cached_support_func_guess
the support function initial guess set by user
Definition: coal/collision_data.h:183
coal::Contact::getDistanceToCollision
CoalScalar getDistanceToCollision(const CollisionRequest &request) const
Definition: coal/collision_data.h:384
coal::ContactPatchResult::getUnusedContactPatch
ContactPatchRef getUnusedContactPatch()
Returns a new unused contact patch from the internal data vector.
Definition: coal/collision_data.h:862
COAL_COMPILER_DIAGNOSTIC_PUSH
#define COAL_COMPILER_DIAGNOSTIC_PUSH
Definition: include/coal/fwd.hh:120
coal::GJK_DEFAULT_TOLERANCE
constexpr CoalScalar GJK_DEFAULT_TOLERANCE
Definition: coal/narrowphase/narrowphase_defaults.h:47
coal::DistanceResult::b1
int b1
information about the nearest point in object 1 if object 1 is mesh or point cloud,...
Definition: coal/collision_data.h:1077
coal::CollisionResult::isCollision
bool isCollision() const
return binary collision result
Definition: coal/collision_data.h:443
COAL_ASSERT
#define COAL_ASSERT(check, message, exception)
Definition: include/coal/fwd.hh:82
coal::GJKConvergenceCriterionType
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
Definition: coal/data_types.h:108
coal::ContactPatch::getNormal
Vec3s getNormal() const
Normal of the contact patch, expressed in the WORLD frame.
Definition: coal/collision_data.h:569
coal::DefaultGuess
@ DefaultGuess
Definition: coal/data_types.h:95
coal::Contact::normal
Vec3s normal
contact normal, pointing from o1 to o2. The normal defined as the normalized separation vector: norma...
Definition: coal/collision_data.h:88
coal::CollisionResult::contacts
std::vector< Contact > contacts
contact information
Definition: coal/collision_data.h:393
coal::ContactPatchRequest::setPatchTolerance
void setPatchTolerance(const CoalScalar patch_tolerance)
Tolerance below which points are added to a contact patch. In details, given two shapes S1 and S2,...
Definition: coal/collision_data.h:798
coal::Transform3s::transform
Vec3s transform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the transform
Definition: coal/math/transform.h:152
coal::ContactPatchResult::m_id_available_patch
size_t m_id_available_patch
Contact patches in m_contact_patches_data can have two statuses: used or unused. This index tracks th...
Definition: coal/collision_data.h:839
coal::internal::updateDistanceLowerBoundFromLeaf
void updateDistanceLowerBoundFromLeaf(const CollisionRequest &, CollisionResult &res, const CoalScalar &distance, const Vec3s &p0, const Vec3s &p1, const Vec3s &normal)
Definition: coal/collision_data.h:1184
coal::QueryResult
base class for all query results
Definition: coal/collision_data.h:275
coal::CollisionRequest::security_margin
CoalScalar security_margin
Distance below which objects are considered in collision. See Collision.
Definition: coal/collision_data.h:328
coal::QueryResult::cached_gjk_guess
Vec3s cached_gjk_guess
stores the last GJK ray when relevant.
Definition: coal/collision_data.h:277
coal::CollisionRequest::enable_distance_lower_bound
bool enable_distance_lower_bound
Whether a lower bound on distance is returned when objects are disjoint.
Definition: coal/collision_data.h:321
coal::Relative
@ Relative
Definition: coal/data_types.h:108
coal::ContactPatchRequest::max_num_patch
size_t max_num_patch
Maximum number of contact patches that will be computed.
Definition: coal/collision_data.h:726
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::DistanceResult::normal
Vec3s normal
normal.
Definition: coal/collision_data.h:1061
coal::ContactPatchResult::numContactPatches
size_t numContactPatches() const
Number of contact patches in the result.
Definition: coal/collision_data.h:859
coal::operator&
CollisionRequestFlag operator&(CollisionRequestFlag a, CollisionRequestFlag b)
Definition: coal/collision_data.h:1208
coal::CachedGuess
@ CachedGuess
Definition: coal/data_types.h:95
coal::QueryRequest::enable_timings
bool enable_timings
enable timings when performing collision/distance request
Definition: coal/collision_data.h:214
coal::CollisionResult::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points. A CollisionResult can have multiple contacts. The nearest points in CollisionResults ...
Definition: coal/collision_data.h:414
coal::Default
@ Default
Definition: coal/data_types.h:104
coal::ContactPatchResult::getContactPatch
const ContactPatch & getContactPatch(const size_t i) const
Const getter for the i-th contact patch of the result.
Definition: coal/collision_data.h:882
coal::Contact::o2
const CollisionGeometry * o2
collision object 2
Definition: coal/collision_data.h:63
coal::distance
COAL_DLLAPI CoalScalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:180
coal::DefaultGJK
@ DefaultGJK
Definition: coal/data_types.h:98
coal::ContactPatch::points
const Polygon & points() const
Const getter for the 2D points in the set.
Definition: coal/collision_data.h:619
coal::Contact::Contact
Contact(const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_)
Definition: coal/collision_data.h:117
isApprox
bool isApprox(const CoalScalar v1, const CoalScalar v2, const CoalScalar tol=1e-6)
Definition: hfields.cpp:518
coal::ContactPatchResult::ContactPatchVector
std::vector< ContactPatch > ContactPatchVector
Definition: coal/collision_data.h:823
coal::NO_REQUEST
@ NO_REQUEST
Definition: coal/collision_data.h:307
coal::ContactPatch::point
Vec2s & point(const size_t i)
Getter for the i-th 2D point in the set.
Definition: coal/collision_data.h:622
coal::GJKVariant
GJKVariant
Variant to use for the GJK algorithm.
Definition: coal/data_types.h:98
collision_object.h
coal::ContactPatch
This structure allows to encode contact patches. A contact patch is defined by a set of points belong...
Definition: coal/collision_data.h:512
coal::ContactPatch::m_points
Polygon m_points
Container for the vertices of the set.
Definition: coal/collision_data.h:553
coal::operator~
CollisionRequestFlag operator~(CollisionRequestFlag a)
Definition: coal/collision_data.h:1198
coal::QueryRequest::cached_gjk_guess
Vec3s cached_gjk_guess
the gjk initial guess set by user
Definition: coal/collision_data.h:180
coal::Contact::b2
int b2
contact primitive in object 2 if object 2 is mesh or point cloud, it is the triangle or point id if o...
Definition: coal/collision_data.h:75
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::DistanceResult::o2
const CollisionGeometry * o2
collision object 2
Definition: coal/collision_data.h:1071
coal::Contact::penetration_depth
CoalScalar penetration_depth
penetration depth
Definition: coal/collision_data.h:105
narrowphase_defaults.h
coal::QueryRequest::gjk_convergence_criterion_type
GJKConvergenceCriterionType gjk_convergence_criterion_type
convergence criterion used to stop GJK
Definition: coal/collision_data.h:201
coal::Transform3s::inverseTransform
Vec3s inverseTransform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the inverse of the transform
Definition: coal/math/transform.h:158
a
list a
coal::CollisionResult::distance_lower_bound
CoalScalar distance_lower_bound
Definition: coal/collision_data.h:401
coal::QueryResult::timings
CPUTimes timings
timings for the given request
Definition: coal/collision_data.h:283
coal::DISTANCE_LOWER_BOUND
@ DISTANCE_LOWER_BOUND
Definition: coal/collision_data.h:306
distance_lower_bound
Definition: distance_lower_bound.py:1
coal::ContactPatch::getPointShape1
Vec3s getPointShape1(const size_t i) const
Get the i-th point of the contact patch, projected back onto the first shape of the collision pair....
Definition: coal/collision_data.h:600
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::DistanceRequest::abs_err
CoalScalar abs_err
Definition: coal/collision_data.h:1014
coal::ContactPatch::direction
PatchDirection direction
Direction of this contact patch.
Definition: coal/collision_data.h:532
res
res
coal::QueryRequest::gjk_max_iterations
size_t gjk_max_iterations
maximum iteration for the GJK algorithm
Definition: coal/collision_data.h:186
coal::ContactPatchRequest::operator==
bool operator==(const ContactPatchRequest &other) const
Whether two ContactPatchRequest are identical or not.
Definition: coal/collision_data.h:813
coal::ContactPatchResult::operator==
bool operator==(const ContactPatchResult &other) const
Whether two ContactPatchResult are identical or not.
Definition: coal/collision_data.h:948
coal::ContactPatch::ContactPatch
ContactPatch(size_t preallocated_size=default_preallocated_size)
Default constructor. Note: the preallocated size does not determine the maximum number of points in t...
Definition: coal/collision_data.h:561
coal::DistanceResult::min_distance
CoalScalar min_distance
minimum distance between two objects. If two objects are in collision and DistanceRequest::enable_sig...
Definition: coal/collision_data.h:1058
coal::constructContactPatchFrameFromContact
void constructContactPatchFrameFromContact(const Contact &contact, ContactPatch &contact_patch)
Construct a frame from a Contact's position and normal. Because both Contact's position and normal ar...
Definition: coal/collision_data.h:704
coal::support_func_guess_t
Eigen::Vector2i support_func_guess_t
Definition: coal/data_types.h:87
coal::CollisionResult::setContact
void setContact(size_t i, const Contact &c)
set the i-th contact calculated
Definition: coal/collision_data.h:462
coal::DistanceRequest
request to the distance computation
Definition: coal/collision_data.h:985
coal::EPA_DEFAULT_MAX_ITERATIONS
constexpr size_t EPA_DEFAULT_MAX_ITERATIONS
Definition: coal/narrowphase/narrowphase_defaults.h:59
coal::CollisionResult::clear
void clear()
clear the results obtained
Definition: coal/collision_data.h:483
coal::operator^
CollisionRequestFlag operator^(CollisionRequestFlag a, CollisionRequestFlag b)
Definition: coal/collision_data.h:1214
coal::CollisionRequest::operator==
bool operator==(const CollisionRequest &other) const
whether two CollisionRequest are the same or not
Definition: coal/collision_data.h:370
c
c
coal::Contact::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points associated to this contact.
Definition: coal/collision_data.h:99
coal::Transform3s::translation
const Vec3s & translation() const
get translation
Definition: coal/math/transform.h:104
coal::CollisionResult::CollisionResult
CollisionResult()
Definition: coal/collision_data.h:417
coal::CollisionResult::addContact
void addContact(const Contact &c)
add one contact into result structure
Definition: coal/collision_data.h:431
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
instead
overload_base_get_item_for_map< Container > instead
coal::ContactPatchResult::ContactPatchResult
ContactPatchResult()
Default constructor.
Definition: coal/collision_data.h:846
coal::CollisionResult
collision result
Definition: coal/collision_data.h:390
coal::DistanceRequest::DistanceRequest
COAL_COMPILER_DIAGNOSTIC_PUSH COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS DistanceRequest(bool enable_nearest_points_=true, bool enable_signed_distance_=true, CoalScalar rel_err_=0.0, CoalScalar abs_err_=0.0)
Definition: coal/collision_data.h:1022
coal::ContactPatch::isSame
bool isSame(const ContactPatch &other, const CoalScalar tol=Eigen::NumTraits< CoalScalar >::dummy_precision()) const
Whether two contact patches are the same or not. Checks for different order of the points.
Definition: coal/collision_data.h:658
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
coal::QueryRequest::epa_max_iterations
size_t epa_max_iterations
max number of iterations for EPA
Definition: coal/collision_data.h:204
coal::DistanceResult
distance result
Definition: coal/collision_data.h:1051
coal::CollisionResult::updateDistanceLowerBound
void updateDistanceLowerBound(const CoalScalar &distance_lower_bound_)
Update the lower bound only if the distance is inferior.
Definition: coal/collision_data.h:424
coal::ContactPatchResult::m_contact_patches_data
ContactPatchVector m_contact_patches_data
Data container for the vector of contact patches.
Definition: coal/collision_data.h:834
octree.pos
pos
Definition: octree.py:7
coal::Transform3s::setIdentity
void setIdentity()
set the transform to be identity transform
Definition: coal/math/transform.h:199
coal::Transform3s::rotation
const Matrix3s & rotation() const
get rotation
Definition: coal/math/transform.h:113
coal::ContactPatchResult
Result for a contact patch computation.
Definition: coal/collision_data.h:822
coal::Contact
Contact information returned by collision.
Definition: coal/collision_data.h:58
coal::Contact::operator!=
bool operator!=(const Contact &other) const
Definition: coal/collision_data.h:162
coal::QueryRequest
base class for all query requests
Definition: coal/collision_data.h:170
coal::ContactPatchRequest
Request for a contact patch computation.
Definition: coal/collision_data.h:724
coal::GJK_DEFAULT_MAX_ITERATIONS
constexpr size_t GJK_DEFAULT_MAX_ITERATIONS
GJK.
Definition: coal/narrowphase/narrowphase_defaults.h:46
coal::ContactPatchRequest::getNumSamplesCurvedShapes
size_t getNumSamplesCurvedShapes() const
Maximum samples to compute the support sets of curved shapes, i.e. when the normal is perpendicular t...
Definition: coal/collision_data.h:793
coal::ContactPatchResult::check
bool check(const ContactPatchRequest &request) const
Return true if this ContactPatchResult is aligned with the ContactPatchRequest given as input.
Definition: coal/collision_data.h:931
coal::ContactPatchRequest::setNumSamplesCurvedShapes
void setNumSamplesCurvedShapes(const size_t num_samples_curved_shapes)
Maximum samples to compute the support sets of curved shapes, i.e. when the normal is perpendicular t...
Definition: coal/collision_data.h:781
coal::ContactPatchRequest::ContactPatchRequest
ContactPatchRequest(size_t max_num_patch=1, size_t num_samples_curved_shapes=ContactPatch::default_preallocated_size, CoalScalar patch_tolerance=1e-3)
Default constructor.
Definition: coal/collision_data.h:761
coal::ContactPatch::tf
Transform3s tf
Frame of the set, expressed in the world coordinates. The z-axis of the frame's rotation is the conta...
Definition: coal/collision_data.h:518
coal::ContactPatch::clear
void clear()
Clear the set.
Definition: coal/collision_data.h:640
coal::ContactPatch::point
const Vec2s & point(const size_t i) const
Const getter for the i-th 2D point in the set.
Definition: coal/collision_data.h:631
coal::ContactPatchResult::set
void set(const ContactPatchRequest &request)
Set up a ContactPatchResult from a ContactPatchRequest
Definition: coal/collision_data.h:919
octree.p1
tuple p1
Definition: octree.py:54
coal::operator|
CollisionRequestFlag operator|(CollisionRequestFlag a, CollisionRequestFlag b)
Definition: coal/collision_data.h:1202
coal::ContactPatchRequest::m_patch_tolerance
CoalScalar m_patch_tolerance
Tolerance below which points are added to a contact patch. In details, given two shapes S1 and S2,...
Definition: coal/collision_data.h:744
coal::DistanceResult::b2
int b2
information about the nearest point in object 2 if object 2 is mesh or point cloud,...
Definition: coal/collision_data.h:1083
coal::QueryRequest::gjk_variant
GJKVariant gjk_variant
whether to enable the Nesterov accleration of GJK
Definition: coal/collision_data.h:195
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::DistanceRequest::rel_err
CoalScalar rel_err
error threshold for approximate distance
Definition: coal/collision_data.h:1013
coal::ContactPatchResult::m_contact_patches
ContactPatchRefVector m_contact_patches
Vector of contact patches of the result.
Definition: coal/collision_data.h:842
coal::EPA_DEFAULT_TOLERANCE
constexpr CoalScalar EPA_DEFAULT_TOLERANCE
Definition: coal/narrowphase/narrowphase_defaults.h:60
coal::GJKInitialGuess
GJKInitialGuess
Initial guess to use for the GJK algorithm DefaultGuess: Vec3s(1, 0, 0) CachedGuess: previous vector ...
Definition: coal/data_types.h:95
coal::Contact::operator<
bool operator<(const Contact &other) const
Definition: coal/collision_data.h:149
coal::CollisionResult::getContacts
const std::vector< Contact > & getContacts() const
Definition: coal/collision_data.h:480
coal::internal::updateDistanceLowerBoundFromBV
void updateDistanceLowerBoundFromBV(const CollisionRequest &, CollisionResult &res, const CoalScalar sqrDistLowerBound)
Definition: coal/collision_data.h:1175
coal::CollisionResult::operator==
bool operator==(const CollisionResult &other) const
whether two CollisionResult are the same or not
Definition: coal/collision_data.h:434
coal::ContactPatch::PatchDirection
PatchDirection
Direction of ContactPatch. When doing collision detection, the convention of Coal is that the normal ...
Definition: coal/collision_data.h:529
coal::Contact::Contact
Contact(const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_, const Vec3s &pos_, const Vec3s &normal_, CoalScalar depth_)
Definition: coal/collision_data.h:125
coal::DistanceResult::update
void update(CoalScalar distance, const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_, const Vec3s &p1, const Vec3s &p2, const Vec3s &normal_)
add distance information into the result
Definition: coal/collision_data.h:1109
coal::operator|=
CollisionRequestFlag & operator|=(CollisionRequestFlag &a, CollisionRequestFlag b)
Definition: coal/collision_data.h:1220
coal::operator^=
CollisionRequestFlag & operator^=(CollisionRequestFlag &a, CollisionRequestFlag b)
Definition: coal/collision_data.h:1230
coal::Contact::o1
const CollisionGeometry * o1
collision object 1
Definition: coal/collision_data.h:60
coal::CollisionRequest::num_max_contacts
size_t num_max_contacts
The maximum number of contacts that can be returned.
Definition: coal/collision_data.h:313
coal::CollisionResult::normal
Vec3s normal
normal associated to nearest_points. Same as CollisionResult::nearest_points but for the normal.
Definition: coal/collision_data.h:405
coal::ContactPatchResult::contactPatch
ContactPatch & contactPatch(const size_t i)
Getter for the i-th contact patch of the result.
Definition: coal/collision_data.h:896
coal::ContactPatch::points
Polygon & points()
Getter for the 2D points in the set.
Definition: coal/collision_data.h:616
coal::ContactPatchRequest::getPatchTolerance
CoalScalar getPatchTolerance() const
Tolerance below which points are added to a contact patch. In details, given two shapes S1 and S2,...
Definition: coal/collision_data.h:810
coal::ContactPatchResult::ContactPatchRef
std::reference_wrapper< ContactPatch > ContactPatchRef
Definition: coal/collision_data.h:824
coal::constructOrthonormalBasisFromVector
Matrix3s constructOrthonormalBasisFromVector(const Vec3s &vec)
Construct othonormal basis from vector. The z-axis is the normalized input vector.
Definition: coal/math/transform.h:262
coal::CollisionRequest::CollisionRequest
CollisionRequest()
Default constructor.
Definition: coal/collision_data.h:358
coal::ContactPatchResult::ContactPatchRefVector
std::vector< ContactPatchRef > ContactPatchRefVector
Definition: coal/collision_data.h:825
COAL_COMPILER_DIAGNOSTIC_POP
#define COAL_COMPILER_DIAGNOSTIC_POP
Definition: include/coal/fwd.hh:121
coal::DistanceRequest::enable_signed_distance
bool enable_signed_distance
whether to compute the penetration depth when objects are in collision. Turning this off can save com...
Definition: coal/collision_data.h:1010
COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
#define COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
Definition: include/coal/fwd.hh:122
coal::CollisionResult::getContact
const Contact & getContact(size_t i) const
get the i-th contact calculated
Definition: coal/collision_data.h:449
coal::DistanceRequest::operator==
COAL_COMPILER_DIAGNOSTIC_POP bool operator==(const DistanceRequest &other) const
whether two DistanceRequest are the same or not
Definition: coal/collision_data.h:1039
coal::ContactPatchResult::ContactPatchResult
ContactPatchResult(const ContactPatchRequest &request)
Constructor using a ContactPatchRequest.
Definition: coal/collision_data.h:853
coal::CollisionResult::getContacts
void getContacts(std::vector< Contact > &contacts_) const
get all the contacts
Definition: coal/collision_data.h:475
num_max_contacts
int num_max_contacts
Definition: test/collision.cpp:73
coal::QueryRequest::enable_cached_gjk_guess
bool enable_cached_gjk_guess
whether enable gjk initial guess @Deprecated Use gjk_initial_guess instead
Definition: coal/collision_data.h:177
coal::CollisionRequestFlag
CollisionRequestFlag
flag declaration for specifying required params in CollisionResult
Definition: coal/collision_data.h:304
coal::DistanceResult::update
void update(CoalScalar distance, const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_)
add distance information into the result
Definition: coal/collision_data.h:1097
timings.h
coal::ContactPatchResult::clear
void clear()
Clears the contact patch result.
Definition: coal/collision_data.h:910
pi
constexpr CoalScalar pi
Definition: collision_node_asserts.cpp:10
coal::ContactPatchRequest::m_num_samples_curved_shapes
size_t m_num_samples_curved_shapes
Maximum samples to compute the support sets of curved shapes, i.e. when the normal is perpendicular t...
Definition: coal/collision_data.h:733
coal::ContactPatch::size
size_t size() const
Returns the number of points in the contact patch.
Definition: coal/collision_data.h:577
logging.h
coal::Contact::b1
int b1
contact primitive in object 1 if object 1 is mesh or point cloud, it is the triangle or point id if o...
Definition: coal/collision_data.h:69
coal::QueryRequest::collision_distance_threshold
CoalScalar collision_distance_threshold
threshold below which a collision is considered.
Definition: coal/collision_data.h:217
coal::DistanceResult::operator==
bool operator==(const DistanceResult &other) const
whether two DistanceResult are the same or not
Definition: coal/collision_data.h:1152
coal::ContactPatchRequest::ContactPatchRequest
ContactPatchRequest(const CollisionRequest &collision_request, size_t num_samples_curved_shapes=ContactPatch::default_preallocated_size, CoalScalar patch_tolerance=1e-3)
Construct a contact patch request from a collision request.
Definition: coal/collision_data.h:771
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::QueryRequest::operator==
bool operator==(const QueryRequest &other) const
whether two QueryRequest are the same or not
Definition: coal/collision_data.h:253
coal::ContactPatchResult::swapObjects
void swapObjects()
Repositions the ContactPatch when they get inverted during their construction.
Definition: coal/collision_data.h:966
coal::CollisionRequest::break_distance
CoalScalar break_distance
Distance below which bounding volumes are broken down. See Collision.
Definition: coal/collision_data.h:332
coal::operator&=
CollisionRequestFlag & operator&=(CollisionRequestFlag &a, CollisionRequestFlag b)
Definition: coal/collision_data.h:1225
COAL_LOG_WARNING
#define COAL_LOG_WARNING(message)
Definition: coal/logging.h:50
coal::DistanceResult::DistanceResult
DistanceResult(CoalScalar min_distance_=(std::numeric_limits< CoalScalar >::max)())
Definition: coal/collision_data.h:1088
coal::DistanceResult::clear
void clear()
clear the result
Definition: coal/collision_data.h:1139
coal::Contact::operator==
bool operator==(const Contact &other) const
Definition: coal/collision_data.h:154
coal::DistanceResult::nearest_points
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
Definition: coal/collision_data.h:1065
coal::CollisionRequest::distance_upper_bound
CoalScalar distance_upper_bound
Distance above which GJK solver makes an early stopping. GJK stops searching for the closest points w...
Definition: coal/collision_data.h:340
coal::ContactPatch::addPoint
void addPoint(const Vec3s &point_3d)
Add a 3D point to the set, expressed in the world frame.
Definition: coal/collision_data.h:584
coal::Vec2s
Eigen::Matrix< CoalScalar, 2, 1 > Vec2s
Definition: coal/data_types.h:78
coal::CollisionResult::numContacts
size_t numContacts() const
number of contacts found
Definition: coal/collision_data.h:446


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