Go to the documentation of this file.
39 #ifndef COAL_COLLISION_DATA_H
40 #define COAL_COLLISION_DATA_H
49 #include "coal/config.hh"
108 static const int NONE = -1;
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());
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());
132 nearest_points{pos_ - (depth_ * normal_ / 2),
133 pos_ + (depth_ * normal_ / 2)},
135 penetration_depth(depth_) {}
145 nearest_points{
p1, p2},
147 penetration_depth(depth_) {}
150 if (b1 == other.
b1)
return b2 < other.
b2;
151 return b1 < other.
b1;
155 return o1 == other.
o1 && o2 == other.
o2 && b1 == other.
b1 &&
176 COAL_DEPRECATED_MESSAGE(Use gjk_initial_guess
instead)
177 bool enable_cached_gjk_guess;
186 size_t gjk_max_iterations;
204 size_t epa_max_iterations;
224 enable_cached_gjk_guess(false),
225 cached_gjk_guess(1, 0, 0),
234 enable_timings(false),
235 collision_distance_threshold(
260 gjk_convergence_criterion_type ==
286 : cached_gjk_guess(
Vec3s::Zero()),
320 COAL_DEPRECATED_MESSAGE(A lower bound on
distance is always computed.)
321 bool enable_distance_lower_bound;
351 enable_contact(flag &
CONTACT),
354 break_distance(1e-3),
355 distance_upper_bound((std::numeric_limits<
CoalScalar>::max)()) {}
360 enable_contact(true),
361 enable_distance_lower_bound(false),
363 break_distance(1e-3),
364 distance_upper_bound((std::numeric_limits<
CoalScalar>::max)()) {}
419 nearest_points[0] = nearest_points[1] = normal =
420 Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN());
435 return contacts == other.
contacts &&
450 if (contacts.size() == 0)
452 "The number of contacts is zero. No Contact can be returned.",
453 std::invalid_argument);
455 if (i < contacts.size())
458 return contacts.back();
463 if (contacts.size() == 0)
465 "The number of contacts is zero. No Contact can be returned.",
466 std::invalid_argument);
468 if (i < contacts.size())
476 contacts_.resize(contacts.size());
477 std::copy(contacts.begin(), contacts.end(), contacts_.begin());
480 const std::vector<Contact>&
getContacts()
const {
return contacts; }
487 nearest_points[0] = nearest_points[1] = normal =
488 Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN());
549 static constexpr
size_t default_preallocated_size = 12;
561 explicit ContactPatch(
size_t preallocated_size = default_preallocated_size)
564 penetration_depth(0) {
565 this->m_points.reserve(preallocated_size);
570 if (this->direction == PatchDirection::INVERTED) {
577 size_t size()
const {
return this->m_points.size(); }
586 this->m_points.emplace_back(point.template head<2>());
591 Vec3s point(0, 0, 0);
592 point.head<2>() = this->point(i);
601 Vec3s point = this->getPoint(i);
602 point -= (this->penetration_depth / 2) * this->getNormal();
610 Vec3s point = this->getPoint(i);
611 point += (this->penetration_depth / 2) * this->getNormal();
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];
627 return this->m_points.back();
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];
636 return this->m_points.back();
641 this->m_points.clear();
643 this->penetration_depth = 0;
651 return this->tf == other.
tf && this->direction == other.
direction &&
653 this->points() == other.
points();
660 Eigen::NumTraits<CoalScalar>::dummy_precision())
const {
672 if (this->direction != other.
direction) {
676 if (this->size() != other.
size()) {
681 for (
size_t i = 0; i < this->size(); ++i) {
683 const Vec3s pi = this->getPoint(i);
684 for (
size_t j = 0; j < other.
size(); ++j) {
686 if (
pi.isApprox(other_pj, tol)) {
710 contact_patch.
direction = ContactPatch::PatchDirection::DEFAULT;
762 size_t num_samples_curved_shapes =
765 : max_num_patch(max_num_patch) {
766 this->setNumSamplesCurvedShapes(num_samples_curved_shapes);
767 this->setPatchTolerance(patch_tolerance);
772 size_t num_samples_curved_shapes =
776 this->setNumSamplesCurvedShapes(num_samples_curved_shapes);
777 this->setPatchTolerance(patch_tolerance);
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;
788 this->m_num_samples_curved_shapes = num_samples_curved_shapes;
794 return this->m_num_samples_curved_shapes;
799 if (patch_tolerance < 0) {
801 "`patch_tolerance` cannot be negative. Setting it to 0 to prevent "
803 this->m_patch_tolerance = Eigen::NumTraits<CoalScalar>::dummy_precision();
805 this->m_patch_tolerance = patch_tolerance;
815 this->getNumSamplesCurvedShapes() ==
847 const size_t max_num_patch = 1;
854 : m_id_available_patch(0) {
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();
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();
883 if (this->m_contact_patches.empty()) {
885 "The number of contact patches is zero. No ContactPatch can be "
887 std::invalid_argument);
889 if (i < this->m_contact_patches.size()) {
890 return this->m_contact_patches[i];
892 return this->m_contact_patches.back();
897 if (this->m_contact_patches.empty()) {
899 "The number of contact patches is zero. No ContactPatch can be "
901 std::invalid_argument);
903 if (i < this->m_contact_patches.size()) {
904 return this->m_contact_patches[i];
906 return this->m_contact_patches.back();
911 this->m_contact_patches.clear();
912 this->m_id_available_patch = 0;
913 for (
ContactPatch& patch : this->m_contact_patches_data) {
920 if (this->m_contact_patches_data.size() < request.
max_num_patch) {
923 for (
ContactPatch& patch : this->m_contact_patches_data) {
932 assert(this->m_contact_patches_data.size() >= request.
max_num_patch);
933 if (this->m_contact_patches_data.size() < request.
max_num_patch) {
937 for (
const ContactPatch& patch : this->m_contact_patches_data) {
939 assert(patch.points().capacity() >=
953 for (
size_t i = 0; i < this->numContactPatches(); ++i) {
956 if (!(patch == other_patch)) {
970 for (
size_t i = 0; i < this->numContactPatches(); ++i) {
975 for (
size_t j = 0; j < patch.
size(); ++j) {
976 patch.
point(i)(0) *= -1.0;
982 struct DistanceResult;
989 COAL_DEPRECATED_MESSAGE(
990 Nearest points are always computed : they are the points of the shapes
993 .\n Use `enable_signed_distance`
if you want to compute
a signed
994 minimum
distance(and thus its corresponding nearest points)
996 bool enable_nearest_points;
1023 bool enable_signed_distance_ =
true,
1025 : enable_nearest_points(enable_nearest_points_),
1026 enable_signed_distance(enable_signed_distance_),
1028 abs_err(abs_err_) {}
1043 enable_nearest_points == other.enable_nearest_points &&
1086 static const int NONE = -1;
1089 CoalScalar min_distance_ = (std::numeric_limits<CoalScalar>::max)())
1090 : min_distance(min_distance_), o1(NULL), o2(NULL), b1(NONE), b2(NONE) {
1092 Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN()));
1093 nearest_points[0] = nearest_points[1] = normal = nan;
1118 nearest_points[0] =
p1;
1119 nearest_points[1] = p2;
1128 o1 = other_result.
o1;
1129 o2 = other_result.
o2;
1130 b1 = other_result.
b1;
1131 b2 = other_result.
b2;
1134 normal = other_result.
normal;
1141 Vec3s::Constant(std::numeric_limits<CoalScalar>::quiet_NaN()));
1142 min_distance = (std::numeric_limits<CoalScalar>::max)();
1147 nearest_points[0] = nearest_points[1] = normal = nan;
1156 normal == other.
normal && o1 == other.
o1 && o2 == other.
o2 &&
1157 b1 == other.
b1 && b2 == other.
b2;
1160 if ((o1 != NULL) ^ (other.
o1 != NULL))
return false;
1161 is_same &= (o1 == other.
o1);
1165 if ((o2 != NULL) ^ (other.
o2 != NULL))
return false;
1166 is_same &= (o2 == other.
o2);
1174 namespace internal {
1179 if (
res.distance_lower_bound <= 0)
return;
1180 CoalScalar new_dlb = std::sqrt(sqrDistLowerBound);
1181 if (new_dlb <
res.distance_lower_bound)
res.distance_lower_bound = new_dlb;
1188 const Vec3s& normal) {
1191 res.nearest_points[0] = p0;
1192 res.nearest_points[1] =
p1;
1193 res.normal = normal;
1205 static_cast<int>(
b));
1211 static_cast<int>(
b));
1217 static_cast<int>(
b));
support_func_guess_t cached_support_func_guess
stores the last support function vertex index, when relevant.
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)....
GJKConvergenceCriterion gjk_convergence_criterion
convergence criterion used to stop GJK
const CollisionGeometry * o1
collision object 1
CoalScalar gjk_tolerance
tolerance for the GJK algorithm. Note: This tolerance determines the precision on the estimated dista...
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
GJKInitialGuess gjk_initial_guess
void update(const DistanceResult &other_result)
add distance information into the result
CoalScalar epa_tolerance
tolerance for EPA. Note: This tolerance determines the precision on the estimated distance between tw...
bool enable_contact
whether the contact information (normal, penetration depth and contact position) will return.
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...
support_func_guess_t cached_support_func_guess
the support function initial guess set by user
#define COAL_COMPILER_DIAGNOSTIC_PUSH
constexpr CoalScalar GJK_DEFAULT_TOLERANCE
int b1
information about the nearest point in object 1 if object 1 is mesh or point cloud,...
bool isCollision() const
return binary collision result
#define COAL_ASSERT(check, message, exception)
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
std::vector< Contact > contacts
contact information
void updateDistanceLowerBoundFromLeaf(const CollisionRequest &, CollisionResult &res, const CoalScalar &distance, const Vec3s &p0, const Vec3s &p1, const Vec3s &normal)
base class for all query results
CoalScalar security_margin
Distance below which objects are considered in collision. See Collision.
Vec3s cached_gjk_guess
stores the last GJK ray when relevant.
bool enable_distance_lower_bound
Whether a lower bound on distance is returned when objects are disjoint.
CollisionRequestFlag operator&(CollisionRequestFlag a, CollisionRequestFlag b)
bool enable_timings
enable timings when performing collision/distance request
std::array< Vec3s, 2 > nearest_points
nearest points. A CollisionResult can have multiple contacts. The nearest points in CollisionResults ...
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.
bool isApprox(const CoalScalar v1, const CoalScalar v2, const CoalScalar tol=1e-6)
GJKVariant
Variant to use for the GJK algorithm.
CollisionRequestFlag operator~(CollisionRequestFlag a)
Vec3s cached_gjk_guess
the gjk initial guess set by user
The geometry for the object for collision or distance computation.
const CollisionGeometry * o2
collision object 2
GJKConvergenceCriterionType gjk_convergence_criterion_type
convergence criterion used to stop GJK
CoalScalar distance_lower_bound
CPUTimes timings
timings for the given request
size_t gjk_max_iterations
maximum iteration for the GJK algorithm
CoalScalar min_distance
minimum distance between two objects. If two objects are in collision and DistanceRequest::enable_sig...
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...
Eigen::Vector2i support_func_guess_t
void setContact(size_t i, const Contact &c)
set the i-th contact calculated
request to the distance computation
constexpr size_t EPA_DEFAULT_MAX_ITERATIONS
void clear()
clear the results obtained
CollisionRequestFlag operator^(CollisionRequestFlag a, CollisionRequestFlag b)
bool operator==(const CollisionRequest &other) const
whether two CollisionRequest are the same or not
void addContact(const Contact &c)
add one contact into result structure
#define COAL_THROW_PRETTY(message, exception)
overload_base_get_item_for_map< Container > instead
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)
request to the collision algorithm
size_t epa_max_iterations
max number of iterations for EPA
void updateDistanceLowerBound(const CoalScalar &distance_lower_bound_)
Update the lower bound only if the distance is inferior.
base class for all query requests
constexpr size_t GJK_DEFAULT_MAX_ITERATIONS
GJK.
CollisionRequestFlag operator|(CollisionRequestFlag a, CollisionRequestFlag b)
int b2
information about the nearest point in object 2 if object 2 is mesh or point cloud,...
GJKVariant gjk_variant
whether to enable the Nesterov accleration of GJK
CoalScalar rel_err
error threshold for approximate distance
constexpr CoalScalar EPA_DEFAULT_TOLERANCE
GJKInitialGuess
Initial guess to use for the GJK algorithm DefaultGuess: Vec3s(1, 0, 0) CachedGuess: previous vector ...
const std::vector< Contact > & getContacts() const
void updateDistanceLowerBoundFromBV(const CollisionRequest &, CollisionResult &res, const CoalScalar sqrDistLowerBound)
bool operator==(const CollisionResult &other) const
whether two CollisionResult are the same or not
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
CollisionRequestFlag & operator|=(CollisionRequestFlag &a, CollisionRequestFlag b)
CollisionRequestFlag & operator^=(CollisionRequestFlag &a, CollisionRequestFlag b)
size_t num_max_contacts
The maximum number of contacts that can be returned.
Vec3s normal
normal associated to nearest_points. Same as CollisionResult::nearest_points but for the normal.
Matrix3s constructOrthonormalBasisFromVector(const Vec3s &vec)
Construct othonormal basis from vector. The z-axis is the normalized input vector.
CollisionRequest()
Default constructor.
#define COAL_COMPILER_DIAGNOSTIC_POP
bool enable_signed_distance
whether to compute the penetration depth when objects are in collision. Turning this off can save com...
#define COAL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
const Contact & getContact(size_t i) const
get the i-th contact calculated
COAL_COMPILER_DIAGNOSTIC_POP bool operator==(const DistanceRequest &other) const
whether two DistanceRequest are the same or not
void getContacts(std::vector< Contact > &contacts_) const
get all the contacts
bool enable_cached_gjk_guess
whether enable gjk initial guess @Deprecated Use gjk_initial_guess instead
CollisionRequestFlag
flag declaration for specifying required params in CollisionResult
void update(CoalScalar distance, const CollisionGeometry *o1_, const CollisionGeometry *o2_, int b1_, int b2_)
add distance information into the result
CoalScalar collision_distance_threshold
threshold below which a collision is considered.
bool operator==(const DistanceResult &other) const
whether two DistanceResult are the same or not
bool operator==(const QueryRequest &other) const
whether two QueryRequest are the same or not
CoalScalar break_distance
Distance below which bounding volumes are broken down. See Collision.
CollisionRequestFlag & operator&=(CollisionRequestFlag &a, CollisionRequestFlag b)
#define COAL_LOG_WARNING(message)
DistanceResult(CoalScalar min_distance_=(std::numeric_limits< CoalScalar >::max)())
void clear()
clear the result
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
CoalScalar distance_upper_bound
Distance above which GJK solver makes an early stopping. GJK stops searching for the closest points w...
Eigen::Matrix< CoalScalar, 2, 1 > Vec2s
size_t numContacts() const
number of contacts found
hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57