coal/internal/shape_shape_contact_patch_func.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2024, INRIA
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #ifndef COAL_INTERNAL_SHAPE_SHAPE_CONTACT_PATCH_FUNC_H
38 #define COAL_INTERNAL_SHAPE_SHAPE_CONTACT_PATCH_FUNC_H
39 
40 #include "coal/collision_data.h"
41 #include "coal/collision_utility.h"
45 
46 namespace coal {
47 
51 template <typename ShapeType1, typename ShapeType2>
53  static void run(const CollisionGeometry* o1, const Transform3s& tf1,
54  const CollisionGeometry* o2, const Transform3s& tf2,
55  const CollisionResult& collision_result,
56  const ContactPatchSolver* csolver,
57  const ContactPatchRequest& request,
58  ContactPatchResult& result) {
59  // Note: see specializations for Plane and Halfspace below.
60  if (!collision_result.isCollision()) {
61  return;
62  }
64  result.check(request),
65  "The contact patch result and request are incompatible (issue of "
66  "contact patch size or maximum number of contact patches). Make sure "
67  "result is initialized with request.",
68  std::logic_error);
69 
70  const ShapeType1& s1 = static_cast<const ShapeType1&>(*o1);
71  const ShapeType2& s2 = static_cast<const ShapeType2&>(*o2);
72  for (size_t i = 0; i < collision_result.numContacts(); ++i) {
73  if (i >= request.max_num_patch) {
74  break;
75  }
76  csolver->setSupportGuess(collision_result.cached_support_func_guess);
77  const Contact& contact = collision_result.getContact(i);
78  ContactPatch& contact_patch = result.getUnusedContactPatch();
79  csolver->computePatch(s1, tf1, s2, tf2, contact, contact_patch);
80  }
81  }
82 };
83 
89 template <bool InvertShapes, typename OtherShapeType, typename PlaneOrHalfspace>
90 void computePatchPlaneOrHalfspace(const OtherShapeType& s1,
91  const Transform3s& tf1,
92  const PlaneOrHalfspace& s2,
93  const Transform3s& tf2,
94  const ContactPatchSolver* csolver,
95  const Contact& contact,
96  ContactPatch& contact_patch) {
99  constructContactPatchFrameFromContact(contact, contact_patch);
101  // Only one point of contact; it has already been computed.
102  contact_patch.addPoint(contact.pos);
103  return;
104  }
105 
106  // We only need to compute the support set in the direction of the normal.
107  // We need to temporarily express the patch in the local frame of shape1.
108  SupportSet& support_set = csolver->support_set_shape1;
109  support_set.tf.rotation().noalias() =
110  tf1.rotation().transpose() * contact_patch.tf.rotation();
111  support_set.tf.translation().noalias() =
112  tf1.rotation().transpose() *
113  (contact_patch.tf.translation() - tf1.translation());
114 
115  // Note: for now, taking into account swept-sphere radius does not change
116  // anything to the support set computations. However it will be used in the
117  // future if we want to store the offsets to the support plane for each point
118  // in a support set.
120  if (InvertShapes) {
121  support_set.direction = ContactPatch::PatchDirection::INVERTED;
122  details::getShapeSupportSet<SupportOptions::WithSweptSphere>(
123  &s1, support_set, csolver->support_guess[1], csolver->supports_data[1],
124  csolver->num_samples_curved_shapes, csolver->patch_tolerance);
125  } else {
126  support_set.direction = ContactPatch::PatchDirection::DEFAULT;
127  details::getShapeSupportSet<SupportOptions::WithSweptSphere>(
128  &s1, support_set, csolver->support_guess[0], csolver->supports_data[0],
129  csolver->num_samples_curved_shapes, csolver->patch_tolerance);
130  }
131  csolver->getResult(contact, &(support_set.points()), contact_patch);
132 }
133 
134 #define PLANE_OR_HSPACE_AND_OTHER_SHAPE_CONTACT_PATCH(PlaneOrHspace) \
135  template <typename OtherShapeType> \
136  struct ComputeShapeShapeContactPatch<OtherShapeType, PlaneOrHspace> { \
137  static void run(const CollisionGeometry* o1, const Transform3s& tf1, \
138  const CollisionGeometry* o2, const Transform3s& tf2, \
139  const CollisionResult& collision_result, \
140  const ContactPatchSolver* csolver, \
141  const ContactPatchRequest& request, \
142  ContactPatchResult& result) { \
143  if (!collision_result.isCollision()) { \
144  return; \
145  } \
146  COAL_ASSERT( \
147  result.check(request), \
148  "The contact patch result and request are incompatible (issue of " \
149  "contact patch size or maximum number of contact patches). Make " \
150  "sure " \
151  "result is initialized with request.", \
152  std::logic_error); \
153  \
154  const OtherShapeType& s1 = static_cast<const OtherShapeType&>(*o1); \
155  const PlaneOrHspace& s2 = static_cast<const PlaneOrHspace&>(*o2); \
156  for (size_t i = 0; i < collision_result.numContacts(); ++i) { \
157  if (i >= request.max_num_patch) { \
158  break; \
159  } \
160  csolver->setSupportGuess(collision_result.cached_support_func_guess); \
161  const Contact& contact = collision_result.getContact(i); \
162  ContactPatch& contact_patch = result.getUnusedContactPatch(); \
163  computePatchPlaneOrHalfspace<false, OtherShapeType, PlaneOrHspace>( \
164  s1, tf1, s2, tf2, csolver, contact, contact_patch); \
165  } \
166  } \
167  }; \
168  \
169  template <typename OtherShapeType> \
170  struct ComputeShapeShapeContactPatch<PlaneOrHspace, OtherShapeType> { \
171  static void run(const CollisionGeometry* o1, const Transform3s& tf1, \
172  const CollisionGeometry* o2, const Transform3s& tf2, \
173  const CollisionResult& collision_result, \
174  const ContactPatchSolver* csolver, \
175  const ContactPatchRequest& request, \
176  ContactPatchResult& result) { \
177  if (!collision_result.isCollision()) { \
178  return; \
179  } \
180  COAL_ASSERT( \
181  result.check(request), \
182  "The contact patch result and request are incompatible (issue of " \
183  "contact patch size or maximum number of contact patches). Make " \
184  "sure " \
185  "result is initialized with request.", \
186  std::logic_error); \
187  \
188  const PlaneOrHspace& s1 = static_cast<const PlaneOrHspace&>(*o1); \
189  const OtherShapeType& s2 = static_cast<const OtherShapeType&>(*o2); \
190  for (size_t i = 0; i < collision_result.numContacts(); ++i) { \
191  if (i >= request.max_num_patch) { \
192  break; \
193  } \
194  csolver->setSupportGuess(collision_result.cached_support_func_guess); \
195  const Contact& contact = collision_result.getContact(i); \
196  ContactPatch& contact_patch = result.getUnusedContactPatch(); \
197  computePatchPlaneOrHalfspace<true, OtherShapeType, PlaneOrHspace>( \
198  s2, tf2, s1, tf1, csolver, contact, contact_patch); \
199  } \
200  } \
201  };
202 
205 
206 #define PLANE_HSPACE_CONTACT_PATCH(PlaneOrHspace1, PlaneOrHspace2) \
207  template <> \
208  struct ComputeShapeShapeContactPatch<PlaneOrHspace1, PlaneOrHspace2> { \
209  static void run(const CollisionGeometry* o1, const Transform3s& tf1, \
210  const CollisionGeometry* o2, const Transform3s& tf2, \
211  const CollisionResult& collision_result, \
212  const ContactPatchSolver* csolver, \
213  const ContactPatchRequest& request, \
214  ContactPatchResult& result) { \
215  COAL_UNUSED_VARIABLE(o1); \
216  COAL_UNUSED_VARIABLE(tf1); \
217  COAL_UNUSED_VARIABLE(o2); \
218  COAL_UNUSED_VARIABLE(tf2); \
219  COAL_UNUSED_VARIABLE(csolver); \
220  if (!collision_result.isCollision()) { \
221  return; \
222  } \
223  COAL_ASSERT( \
224  result.check(request), \
225  "The contact patch result and request are incompatible (issue of " \
226  "contact patch size or maximum number of contact patches). Make " \
227  "sure " \
228  "result is initialized with request.", \
229  std::logic_error); \
230  \
231  for (size_t i = 0; i < collision_result.numContacts(); ++i) { \
232  if (i >= request.max_num_patch) { \
233  break; \
234  } \
235  const Contact& contact = collision_result.getContact(i); \
236  ContactPatch& contact_patch = result.getUnusedContactPatch(); \
237  constructContactPatchFrameFromContact(contact, contact_patch); \
238  contact_patch.addPoint(contact.pos); \
239  } \
240  } \
241  };
242 
243 PLANE_HSPACE_CONTACT_PATCH(Plane, Plane)
244 PLANE_HSPACE_CONTACT_PATCH(Plane, Halfspace)
245 PLANE_HSPACE_CONTACT_PATCH(Halfspace, Plane)
246 PLANE_HSPACE_CONTACT_PATCH(Halfspace, Halfspace)
247 
248 #undef PLANE_OR_HSPACE_AND_OTHER_SHAPE_CONTACT_PATCH
249 #undef PLANE_HSPACE_CONTACT_PATCH
250 
251 template <typename ShapeType1, typename ShapeType2>
253  const CollisionGeometry* o2, const Transform3s& tf2,
254  const CollisionResult& collision_result,
255  const ContactPatchSolver* csolver,
256  const ContactPatchRequest& request,
257  ContactPatchResult& result) {
259  o1, tf1, o2, tf2, collision_result, csolver, request, result);
260 }
261 
262 } // namespace coal
263 
264 #endif
coal::Contact::pos
Vec3s pos
contact position, in world space
Definition: coal/collision_data.h:102
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
PLANE_HSPACE_CONTACT_PATCH
#define PLANE_HSPACE_CONTACT_PATCH(PlaneOrHspace1, PlaneOrHspace2)
Definition: coal/internal/shape_shape_contact_patch_func.h:206
coal::ContactPatchSolver::supports_data
std::array< ShapeSupportData, 2 > supports_data
Temporary data to compute the support sets on each shape.
Definition: coal/contact_patch/contact_patch_solver.h:110
coal::ContactPatchSolver::support_guess
support_func_guess_t support_guess
Guess for the support sets computation.
Definition: coal/contact_patch/contact_patch_solver.h:113
coal::ContactPatchResult::getUnusedContactPatch
ContactPatchRef getUnusedContactPatch()
Returns a new unused contact patch from the internal data vector.
Definition: coal/collision_data.h:862
coal::computePatchPlaneOrHalfspace
void computePatchPlaneOrHalfspace(const OtherShapeType &s1, const Transform3s &tf1, const PlaneOrHalfspace &s2, const Transform3s &tf2, const ContactPatchSolver *csolver, const Contact &contact, ContactPatch &contact_patch)
Computes the contact patch between a Plane/Halfspace and another shape.
Definition: coal/internal/shape_shape_contact_patch_func.h:90
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
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
collision_data.h
coal::ContactPatchSolver::setSupportGuess
void setSupportGuess(const support_func_guess_t guess) const
Sets the support guess used during support set computation of shapes s1 and s2.
Definition: coal/contact_patch/contact_patch_solver.h:153
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
narrowphase.h
coal::shape_traits
Definition: coal/shape/geometric_shapes_traits.h:55
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::ContactPatchSolver::computePatch
void computePatch(const ShapeType1 &s1, const Transform3s &tf1, const ShapeType2 &s2, const Transform3s &tf2, const Contact &contact, ContactPatch &contact_patch) const
Main API of the solver: compute a contact patch from a contact between shapes s1 and s2....
coal::ContactPatchSolver::num_samples_curved_shapes
size_t num_samples_curved_shapes
Number of points sampled for Cone and Cylinder when the normal is orthogonal to the shapes' basis....
Definition: coal/contact_patch/contact_patch_solver.h:97
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::ContactPatchSolver::support_set_shape1
SupportSet support_set_shape1
Holder for support set of shape 1, used for internal computation. After computePatch has been called,...
Definition: coal/contact_patch/contact_patch_solver.h:117
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::ContactPatch::direction
PatchDirection direction
Direction of this contact patch.
Definition: coal/collision_data.h:532
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_UNUSED_VARIABLE
#define COAL_UNUSED_VARIABLE(var)
Definition: include/coal/fwd.hh:56
coal::ShapeShapeContactPatch
void ShapeShapeContactPatch(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionResult &collision_result, const ContactPatchSolver *csolver, const ContactPatchRequest &request, ContactPatchResult &result)
Definition: coal/internal/shape_shape_contact_patch_func.h:252
coal::Transform3s::translation
const Vec3s & translation() const
get translation
Definition: coal/math/transform.h:104
coal::CollisionResult
collision result
Definition: coal/collision_data.h:390
geometric_shapes_traits.h
coal::ContactPatchSolver::patch_tolerance
CoalScalar patch_tolerance
Tolerance below which points are added to the shapes support sets. See ContactPatchRequest::m_patch_t...
Definition: coal/contact_patch/contact_patch_solver.h:101
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
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::ContactPatchRequest
Request for a contact patch computation.
Definition: coal/collision_data.h:724
coal::ComputeShapeShapeContactPatch
Shape-shape contact patch computation. Assumes that csolver and the ContactPatchResult have already b...
Definition: coal/internal/shape_shape_contact_patch_func.h:52
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::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::ComputeShapeShapeContactPatch::run
static void run(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionResult &collision_result, const ContactPatchSolver *csolver, const ContactPatchRequest &request, ContactPatchResult &result)
Definition: coal/internal/shape_shape_contact_patch_func.h:53
coal::ContactPatch::points
Polygon & points()
Getter for the 2D points in the set.
Definition: coal/collision_data.h:616
coal::CollisionResult::getContact
const Contact & getContact(size_t i) const
get the i-th contact calculated
Definition: coal/collision_data.h:449
collision_utility.h
coal::ContactPatchSolver
Solver to compute contact patches, i.e. the intersection between two contact surfaces projected onto ...
Definition: coal/contact_patch/contact_patch_solver.h:59
contact_patch_solver.h
coal::ContactPatchSolver::getResult
void getResult(const Contact &contact, const ContactPatch::Polygon *result, ContactPatch &contact_patch) const
Retrieve result, adds a post-processing step if result has bigger size than this->max_patch_size.
coal::details::SupportOptions
SupportOptions
Options for the computation of support points. NoSweptSphere option is used when the support function...
Definition: coal/narrowphase/support_functions.h:58
PLANE_OR_HSPACE_AND_OTHER_SHAPE_CONTACT_PATCH
#define PLANE_OR_HSPACE_AND_OTHER_SHAPE_CONTACT_PATCH(PlaneOrHspace)
Definition: coal/internal/shape_shape_contact_patch_func.h:134
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::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:59