coal/contact_patch/contact_patch_solver.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  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  * * Neither the name of INRIA nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
36 #ifndef COAL_CONTACT_PATCH_SOLVER_H
37 #define COAL_CONTACT_PATCH_SOLVER_H
38 
39 #include "coal/collision_data.h"
40 #include "coal/logging.h"
41 #include "coal/narrowphase/gjk.h"
42 
43 namespace coal {
44 
59 struct COAL_DLLAPI ContactPatchSolver {
60  // Note: `ContactPatch` is an alias for `SupportSet`.
61  // The two can be used interchangeably.
64 
84  typedef void (*SupportSetFunction)(const ShapeBase* shape,
85  SupportSet& support_set, int& hint,
86  ShapeSupportData& support_data,
87  size_t num_sampled_supports,
88  CoalScalar tol);
89 
91  static constexpr size_t default_num_preallocated_supports = 16;
92 
98 
102 
104  mutable SupportSetFunction supportFuncShape1;
105 
107  mutable SupportSetFunction supportFuncShape2;
108 
110  mutable std::array<ShapeSupportData, 2> supports_data;
111 
114 
118 
122 
125 
130  mutable std::vector<bool> added_to_patch;
131 
133  explicit ContactPatchSolver() {
134  const size_t num_contact_patch = 1;
135  const size_t preallocated_patch_size =
137  const CoalScalar patch_tolerance = 1e-3;
138  const ContactPatchRequest request(num_contact_patch,
139  preallocated_patch_size, patch_tolerance);
140  this->set(request);
141  }
142 
144  explicit ContactPatchSolver(const ContactPatchRequest& request) {
145  this->set(request);
146  }
147 
149  void set(const ContactPatchRequest& request);
150 
153  void setSupportGuess(const support_func_guess_t guess) const {
154  this->support_guess = guess;
155  }
156 
162  template <typename ShapeType1, typename ShapeType2>
163  void computePatch(const ShapeType1& s1, const Transform3s& tf1,
164  const ShapeType2& s2, const Transform3s& tf2,
165  const Contact& contact, ContactPatch& contact_patch) const;
166 
168  template <typename ShapeType1, typename ShapeType2>
169  void reset(const ShapeType1& shape1, const Transform3s& tf1,
170  const ShapeType2& shape2, const Transform3s& tf2,
171  const ContactPatch& contact_patch) const;
172 
175  void getResult(const Contact& contact, const ContactPatch::Polygon* result,
176  ContactPatch& contact_patch) const;
177 
183  static Vec2s computeLineSegmentIntersection(const Vec2s& a, const Vec2s& b,
184  const Vec2s& c, const Vec2s& d);
185 
187  static SupportSetFunction makeSupportSetFunction(
188  const ShapeBase* shape, ShapeSupportData& support_data);
189 
190  bool operator==(const ContactPatchSolver& other) const {
191  return this->num_samples_curved_shapes == other.num_samples_curved_shapes &&
192  this->patch_tolerance == other.patch_tolerance &&
193  this->support_guess == other.support_guess &&
194  this->support_set_shape1 == other.support_set_shape1 &&
195  this->support_set_shape2 == other.support_set_shape2 &&
196  this->support_set_buffer == other.support_set_buffer &&
197  this->added_to_patch == other.added_to_patch &&
198  this->supportFuncShape1 == other.supportFuncShape1 &&
199  this->supportFuncShape2 == other.supportFuncShape2;
200  }
201 
202  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
203 };
204 
205 } // namespace coal
206 
207 #include "coal/contact_patch/contact_patch_solver.hxx"
208 
209 #endif // COAL_CONTACT_PATCH_SOLVER_H
coal::ContactPatch::Polygon
std::vector< Vec2s > Polygon
Definition: coal/collision_data.h:514
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::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::ContactPatchSolver::operator==
bool operator==(const ContactPatchSolver &other) const
Definition: coal/contact_patch/contact_patch_solver.h:190
coal::details::ShapeSupportData
Stores temporary data for the computation of support points.
Definition: coal/narrowphase/support_functions.h:80
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::ContactPatchSolver::support_set_shape2
SupportSet support_set_shape2
Holder for support set of shape 2, used for internal computation. After computePatch has been called,...
Definition: coal/contact_patch/contact_patch_solver.h:121
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
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::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::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::support_func_guess_t
Eigen::Vector2i support_func_guess_t
Definition: coal/data_types.h:87
coal::ShapeBase
Base class for all basic geometric shapes.
Definition: coal/shape/geometric_shapes.h:58
coal::ContactPatchSolver::ContactPatchSolver
ContactPatchSolver(const ContactPatchRequest &request)
Construct the solver with a ContactPatchRequest.
Definition: coal/contact_patch/contact_patch_solver.h:144
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::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::ContactPatchSolver::ContactPatchSolver
ContactPatchSolver()
Default constructor.
Definition: coal/contact_patch/contact_patch_solver.h:133
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::ContactPatchSolver::supportFuncShape2
SupportSetFunction supportFuncShape2
Support set function for shape s2.
Definition: coal/contact_patch/contact_patch_solver.h:107
coal::ContactPatchSolver::added_to_patch
std::vector< bool > added_to_patch
Tracks which point of the Sutherland-Hodgman result have been added to the contact patch....
Definition: coal/contact_patch/contact_patch_solver.h:130
coal::ContactPatchSolver::support_set_buffer
SupportSet support_set_buffer
Temporary support set used for the Sutherland-Hodgman algorithm.
Definition: coal/contact_patch/contact_patch_solver.h:124
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::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
gjk.h
logging.h
coal::ContactPatchSolver::supportFuncShape1
SupportSetFunction supportFuncShape1
Support set function for shape s1.
Definition: coal/contact_patch/contact_patch_solver.h:104
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::Vec2s
Eigen::Matrix< CoalScalar, 2, 1 > Vec2s
Definition: coal/data_types.h:78


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