coal/narrowphase/gjk.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) 2021-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_GJK_H
40 #define COAL_GJK_H
41 
42 #include <vector>
43 
45 
46 namespace coal {
47 
48 namespace details {
49 
53 struct COAL_DLLAPI GJK {
54  struct COAL_DLLAPI SimplexV {
56  Vec3s w0, w1;
60  };
61 
62  typedef unsigned char vertex_id_t;
63 
71  struct COAL_DLLAPI Simplex {
73  SimplexV* vertex[4];
76 
77  Simplex() {}
78 
79  void reset() {
80  rank = 0;
81  for (size_t i = 0; i < 4; ++i) vertex[i] = nullptr;
82  }
83  };
84 
94  enum Status {
100  Collision
101  };
102 
103  public:
109 
119  Simplex* simplex; // Pointer to the result of the last run of GJK.
120 
121  private:
122  // max_iteration and tolerance are made private
123  // because they are meant to be set by the `reset` function.
126 
127  SimplexV store_v[4];
128  SimplexV* free_v[4];
131  Simplex simplices[2];
132  size_t iterations;
134 
135  public:
143  GJK(size_t max_iterations_, CoalScalar tolerance_)
144  : max_iterations(max_iterations_), tolerance(tolerance_) {
145  COAL_ASSERT(tolerance_ > 0, "Tolerance must be positive.",
146  std::invalid_argument);
147  initialize();
148  }
149 
153  void reset(size_t max_iterations_, CoalScalar tolerance_);
154 
156  Status evaluate(
157  const MinkowskiDiff& shape, const Vec3s& guess,
158  const support_func_guess_t& supportHint = support_func_guess_t::Zero());
159 
162  inline void getSupport(const Vec3s& d, SimplexV& sv,
163  support_func_guess_t& hint) const {
164  shape->support(d, sv.w0, sv.w1, hint);
165  sv.w = sv.w0 - sv.w1;
166  }
167 
169  bool encloseOrigin();
170 
173  inline Simplex* getSimplex() const { return simplex; }
174 
176  bool hasClosestPoints() const { return distance < distance_upper_bound; }
177 
184  void getWitnessPointsAndNormal(const MinkowskiDiff& shape, Vec3s& w0,
185  Vec3s& w1, Vec3s& normal) const;
186 
188  Vec3s getGuessFromSimplex() const;
189 
195  distance_upper_bound = dup;
196  }
197 
200  bool checkConvergence(const Vec3s& w, const CoalScalar& rl, CoalScalar& alpha,
201  const CoalScalar& omega) const;
202 
204  size_t getNumMaxIterations() const { return max_iterations; }
205 
207  CoalScalar getTolerance() const { return tolerance; }
208 
210  size_t getNumIterations() const { return iterations; }
211 
215  return iterations_momentum_stop;
216  }
217 
218  private:
222  void initialize();
223 
225  inline void removeVertex(Simplex& simplex);
226 
228  inline void appendVertex(Simplex& simplex, const Vec3s& v,
229  support_func_guess_t& hint);
230 
246  bool projectLineOrigin(const Simplex& current, Simplex& next);
247 
250  bool projectTriangleOrigin(const Simplex& current, Simplex& next);
251 
254  bool projectTetrahedraOrigin(const Simplex& current, Simplex& next);
255 };
256 
258 struct COAL_DLLAPI EPA {
260  struct COAL_DLLAPI SimplexFace {
263  bool ignore; // If the origin does not project inside the face, we
264  // ignore this face.
265  size_t vertex_id[3]; // Index of vertex in sv_store.
266  SimplexFace* adjacent_faces[3]; // A face has three adjacent faces.
267  SimplexFace* prev_face; // The previous face in the list.
268  SimplexFace* next_face; // The next face in the list.
269  size_t adjacent_edge[3]; // Each face has 3 edges: `0`, `1` and `2`.
270  // The i-th adjacent face is bound (to this face)
271  // along its `adjacent_edge[i]`-th edge
272  // (with 0 <= i <= 2).
273  size_t pass;
274 
275  SimplexFace() : n(Vec3s::Zero()), ignore(false) {};
276  };
277 
281  struct COAL_DLLAPI SimplexFaceList {
283  size_t count;
284  SimplexFaceList() : root(nullptr), count(0) {}
285 
286  void reset() {
287  root = nullptr;
288  count = 0;
289  }
290 
291  void append(SimplexFace* face) {
292  face->prev_face = nullptr;
293  face->next_face = root;
294  if (root != nullptr) root->prev_face = face;
295  root = face;
296  ++count;
297  }
298 
299  void remove(SimplexFace* face) {
300  if (face->next_face != nullptr)
301  face->next_face->prev_face = face->prev_face;
302  if (face->prev_face != nullptr)
303  face->prev_face->next_face = face->next_face;
304  if (face == root) root = face->next_face;
305  --count;
306  }
307  };
308 
311  static inline void bind(SimplexFace* fa, size_t ea, SimplexFace* fb,
312  size_t eb) {
313  assert(ea == 0 || ea == 1 || ea == 2);
314  assert(eb == 0 || eb == 1 || eb == 2);
315  fa->adjacent_edge[ea] = eb;
316  fa->adjacent_faces[ea] = fb;
317  fb->adjacent_edge[eb] = ea;
318  fb->adjacent_faces[eb] = fa;
319  }
320 
321  struct COAL_DLLAPI SimplexHorizon {
322  SimplexFace* current_face; // current face in the horizon
323  SimplexFace* first_face; // first face in the horizon
324  size_t num_faces; // number of faces in the horizon
326  : current_face(nullptr), first_face(nullptr), num_faces(0) {}
327  };
328 
329  enum Status {
330  DidNotRun = -1,
331  Failed = 0,
332  Valid = 1,
333  AccuracyReached = 1 << 1 | Valid,
334  Degenerated = 1 << 1 | Failed,
335  NonConvex = 2 << 1 | Failed,
336  InvalidHull = 3 << 1 | Failed,
337  OutOfFaces = 4 << 1 | Failed,
338  OutOfVertices = 5 << 1 | Failed,
339  FallBack = 6 << 1 | Failed
340  };
341 
342  public:
349 
350  private:
351  // max_iteration and tolerance are made private
352  // because they are meant to be set by the `reset` function.
355 
356  std::vector<SimplexVertex> sv_store;
357  std::vector<SimplexFace> fc_store;
359  size_t num_vertices; // number of vertices in polytpoe constructed by EPA
360  size_t iterations;
361 
362  public:
363  EPA(size_t max_iterations_, CoalScalar tolerance_)
364  : max_iterations(max_iterations_), tolerance(tolerance_) {
365  initialize();
366  }
367 
370  EPA(const EPA& other)
371  : max_iterations(other.max_iterations),
372  tolerance(other.tolerance),
373  sv_store(other.sv_store),
374  fc_store(other.fc_store) {
375  initialize();
376  }
377 
379  size_t getNumMaxIterations() const { return max_iterations; }
380 
382  size_t getNumMaxVertices() const { return sv_store.size(); }
383 
385  size_t getNumMaxFaces() const { return fc_store.size(); }
386 
388  CoalScalar getTolerance() const { return tolerance; }
389 
391  size_t getNumIterations() const { return iterations; }
392 
394  size_t getNumVertices() const { return num_vertices; }
395 
397  size_t getNumFaces() const { return hull.count; }
398 
407  void reset(size_t max_iterations, CoalScalar tolerance);
408 
412  Status evaluate(GJK& gjk, const Vec3s& guess);
413 
421  void getWitnessPointsAndNormal(const MinkowskiDiff& shape, Vec3s& w0,
422  Vec3s& w1, Vec3s& normal) const;
423 
424  private:
428  void initialize();
429 
430  bool getEdgeDist(SimplexFace* face, const SimplexVertex& a,
431  const SimplexVertex& b, CoalScalar& dist);
432 
436  SimplexFace* newFace(size_t id_a, size_t id_b, size_t id_vertex,
437  bool force = false);
438 
440  SimplexFace* findClosestFace();
441 
443  bool expand(size_t pass, const SimplexVertex& w, SimplexFace* f, size_t e,
444  SimplexHorizon& horizon);
445 
446  // @brief Use this function to debug expand if needed.
447  // void PrintExpandLooping(const SimplexFace* f, const SimplexVertex& w);
448 };
449 
450 } // namespace details
451 
452 } // namespace coal
453 
454 #endif
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::details::EPA::SimplexHorizon::current_face
SimplexFace * current_face
Definition: coal/narrowphase/gjk.h:322
coal::details::EPA::Status
Status
Definition: coal/narrowphase/gjk.h:329
coal::details::EPA::SimplexFace::next_face
SimplexFace * next_face
Definition: coal/narrowphase/gjk.h:268
coal::details::EPA::SimplexFaceList::count
size_t count
Definition: coal/narrowphase/gjk.h:283
coal::details::EPA::SimplexFaceList::reset
void reset()
Definition: coal/narrowphase/gjk.h:286
coal::details::GJK::getNumMaxIterations
size_t getNumMaxIterations() const
Get the max number of iterations of GJK.
Definition: coal/narrowphase/gjk.h:204
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::details::EPA::SimplexFace::ignore
bool ignore
Definition: coal/narrowphase/gjk.h:263
coal::details::GJK::Failed
@ Failed
Definition: coal/narrowphase/gjk.h:96
coal::details::EPA::fc_store
std::vector< SimplexFace > fc_store
Definition: coal/narrowphase/gjk.h:357
coal::details::EPA::stock
SimplexFaceList stock
Definition: coal/narrowphase/gjk.h:358
coal::details::EPA::num_vertices
size_t num_vertices
Definition: coal/narrowphase/gjk.h:359
coal::details::EPA::EPA
EPA(size_t max_iterations_, CoalScalar tolerance_)
Definition: coal/narrowphase/gjk.h:363
coal::details::GJK::Simplex::reset
void reset()
Definition: coal/narrowphase/gjk.h:79
coal::details::GJK::ray
Vec3s ray
Definition: coal/narrowphase/gjk.h:111
coal::details::EPA::getNumIterations
size_t getNumIterations() const
Get the number of iterations of the last run of EPA.
Definition: coal/narrowphase/gjk.h:391
coal::details::GJK::shape
MinkowskiDiff const * shape
Definition: coal/narrowphase/gjk.h:110
coal::details::GJK::hasClosestPoints
bool hasClosestPoints() const
Tells whether the closest points are available.
Definition: coal/narrowphase/gjk.h:176
coal::details::GJK::iterations_momentum_stop
size_t iterations_momentum_stop
Definition: coal/narrowphase/gjk.h:133
coal::details::EPA::getNumMaxIterations
size_t getNumMaxIterations() const
Get the max number of iterations of EPA.
Definition: coal/narrowphase/gjk.h:379
coal::details::MinkowskiDiff
Minkowski difference class of two shapes.
Definition: coal/narrowphase/minkowski_difference.h:53
coal::details::GJK::Status
Status
Status of the GJK algorithm: DidNotRun: GJK has not been run. Failed: GJK did not converge (it exceed...
Definition: coal/narrowphase/gjk.h:94
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::details::GJK::gjk_variant
GJKVariant gjk_variant
Definition: coal/narrowphase/gjk.h:106
coal::details::GJK::NoCollisionEarlyStopped
@ NoCollisionEarlyStopped
Definition: coal/narrowphase/gjk.h:97
coal::details::EPA::SimplexHorizon::SimplexHorizon
SimplexHorizon()
Definition: coal/narrowphase/gjk.h:325
coal::details::EPA::SimplexFace::adjacent_edge
size_t adjacent_edge[3]
Definition: coal/narrowphase/gjk.h:269
coal::details::EPA
class for EPA algorithm
Definition: coal/narrowphase/gjk.h:258
coal::details::EPA::SimplexFace::n
Vec3s n
Definition: coal/narrowphase/gjk.h:261
coal::details::EPA::result
GJK::Simplex result
Definition: coal/narrowphase/gjk.h:344
coal::details::GJK::getNumIterations
size_t getNumIterations() const
Get the number of iterations of the last run of GJK.
Definition: coal/narrowphase/gjk.h:210
coal::details::EPA::SimplexHorizon::num_faces
size_t num_faces
Definition: coal/narrowphase/gjk.h:324
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::details::GJK::setDistanceEarlyBreak
void setDistanceEarlyBreak(const CoalScalar &dup)
Distance threshold for early break. GJK stops when it proved the distance is more than this threshold...
Definition: coal/narrowphase/gjk.h:194
coal::details::EPA::SimplexFace
Definition: coal/narrowphase/gjk.h:260
nullptr
#define nullptr
Definition: assimp.cpp:36
coal::details::MinkowskiDiff::support
void support(const Vec3s &dir, Vec3s &supp0, Vec3s &supp1, support_func_guess_t &hint) const
Support function for the pair of shapes. This method assumes set has already been called.
Definition: coal/narrowphase/minkowski_difference.h:174
coal::details::GJK::tolerance
CoalScalar tolerance
Definition: coal/narrowphase/gjk.h:125
coal::details::GJK::convergence_criterion
GJKConvergenceCriterion convergence_criterion
Definition: coal/narrowphase/gjk.h:107
coal::details::EPA::SimplexHorizon::first_face
SimplexFace * first_face
Definition: coal/narrowphase/gjk.h:323
coal::details::GJK::Simplex
A simplex is a set of up to 4 vertices. Its rank is the number of vertices it contains.
Definition: coal/narrowphase/gjk.h:71
coal::details::GJK::distance_upper_bound
CoalScalar distance_upper_bound
Definition: coal/narrowphase/gjk.h:104
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::GJKVariant
GJKVariant
Variant to use for the GJK algorithm.
Definition: coal/data_types.h:98
coal::details::EPA::SimplexFace::pass
size_t pass
Definition: coal/narrowphase/gjk.h:273
coal::details::GJK::Simplex::Simplex
Simplex()
Definition: coal/narrowphase/gjk.h:77
coal::details::GJK::SimplexV::w1
Vec3s w1
Definition: coal/narrowphase/gjk.h:56
coal::details::GJK::SimplexV::w
Vec3s w
support vector (i.e., the furthest point on the shape along the support direction)
Definition: coal/narrowphase/gjk.h:59
coal::details::GJK::getSimplex
Simplex * getSimplex() const
get the underlying simplex using in GJK, can be used for cache in next iteration
Definition: coal/narrowphase/gjk.h:173
coal::details::EPA::getNumMaxVertices
size_t getNumMaxVertices() const
Get the max number of vertices of EPA.
Definition: coal/narrowphase/gjk.h:382
coal::details::GJK::iterations
size_t iterations
Definition: coal/narrowphase/gjk.h:132
coal::details::EPA::SimplexFace::SimplexFace
SimplexFace()
Definition: coal/narrowphase/gjk.h:275
coal::details::GJK::GJK
GJK(size_t max_iterations_, CoalScalar tolerance_)
Definition: coal/narrowphase/gjk.h:143
coal::details::EPA::SimplexFaceList::root
SimplexFace * root
Definition: coal/narrowphase/gjk.h:282
coal::support_func_guess_t
Eigen::Vector2i support_func_guess_t
Definition: coal/data_types.h:87
coal::details::EPA::closest_face
SimplexFace * closest_face
Definition: coal/narrowphase/gjk.h:348
coal::details::EPA::bind
static void bind(SimplexFace *fa, size_t ea, SimplexFace *fb, size_t eb)
We bind the face fa along its edge ea to the face fb along its edge fb.
Definition: coal/narrowphase/gjk.h:311
coal::details::EPA::getNumMaxFaces
size_t getNumMaxFaces() const
Get the max number of faces of EPA.
Definition: coal/narrowphase/gjk.h:385
d
d
coal::details::EPA::SimplexVertex
GJK::SimplexV SimplexVertex
Definition: coal/narrowphase/gjk.h:259
coal::details::GJK::distance
CoalScalar distance
The distance between the two shapes, computed by GJK. If the distance is below GJK's threshold,...
Definition: coal/narrowphase/gjk.h:118
coal::details::GJK::Simplex::rank
vertex_id_t rank
size of simplex (number of vertices)
Definition: coal/narrowphase/gjk.h:75
coal::details::GJK::convergence_criterion_type
GJKConvergenceCriterionType convergence_criterion_type
Definition: coal/narrowphase/gjk.h:108
coal::details::EPA::SimplexFaceList::remove
void remove(SimplexFace *face)
Definition: coal/narrowphase/gjk.h:299
coal::details::GJK::getSupport
void getSupport(const Vec3s &d, SimplexV &sv, support_func_guess_t &hint) const
apply the support function along a direction, the result is return in sv
Definition: coal/narrowphase/gjk.h:162
coal::details::EPA::iterations
size_t iterations
Definition: coal/narrowphase/gjk.h:360
coal::details::GJK::CollisionWithPenetrationInformation
@ CollisionWithPenetrationInformation
Definition: coal/narrowphase/gjk.h:99
minkowski_difference.h
coal::details::EPA::SimplexFace::d
CoalScalar d
Definition: coal/narrowphase/gjk.h:262
coal::details::EPA::SimplexFaceList::append
void append(SimplexFace *face)
Definition: coal/narrowphase/gjk.h:291
coal::details::EPA::SimplexHorizon
Definition: coal/narrowphase/gjk.h:321
coal::details::GJK::nfree
vertex_id_t nfree
Definition: coal/narrowphase/gjk.h:129
coal::details::EPA::status
Status status
Definition: coal/narrowphase/gjk.h:343
coal::details::GJK::getNumIterationsMomentumStopped
size_t getNumIterationsMomentumStopped() const
Get GJK number of iterations before momentum stops. Only usefull if the Nesterov or Polyak accelerati...
Definition: coal/narrowphase/gjk.h:214
coal::details::EPA::getNumVertices
size_t getNumVertices() const
Get the number of vertices in the polytope of the last run of EPA.
Definition: coal/narrowphase/gjk.h:394
coal::details::GJK::status
Status status
Definition: coal/narrowphase/gjk.h:105
coal::details::GJK::NoCollision
@ NoCollision
Definition: coal/narrowphase/gjk.h:98
coal::details::EPA::SimplexFace::adjacent_faces
SimplexFace * adjacent_faces[3]
Definition: coal/narrowphase/gjk.h:266
coal::details::EPA::EPA
EPA(const EPA &other)
Copy constructor of EPA. Mostly needed for the copy constructor of GJKSolver.
Definition: coal/narrowphase/gjk.h:370
coal::details::GJK::SimplexV::w0
Vec3s w0
support vector for shape 0 and 1.
Definition: coal/narrowphase/gjk.h:56
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::details::GJK::DidNotRun
@ DidNotRun
Definition: coal/narrowphase/gjk.h:95
coal::details::EPA::tolerance
CoalScalar tolerance
Definition: coal/narrowphase/gjk.h:354
coal::details::EPA::SimplexFaceList::SimplexFaceList
SimplexFaceList()
Definition: coal/narrowphase/gjk.h:284
coal::details::EPA::normal
Vec3s normal
Definition: coal/narrowphase/gjk.h:345
coal::details::EPA::getNumFaces
size_t getNumFaces() const
Get the number of faces in the polytope of the last run of EPA.
Definition: coal/narrowphase/gjk.h:397
coal::details::EPA::getTolerance
CoalScalar getTolerance() const
Get the tolerance of EPA.
Definition: coal/narrowphase/gjk.h:388
coal::details::EPA::SimplexFace::prev_face
SimplexFace * prev_face
Definition: coal/narrowphase/gjk.h:267
coal::details::GJK::getTolerance
CoalScalar getTolerance() const
Get the tolerance of GJK.
Definition: coal/narrowphase/gjk.h:207
coal::details::GJK::SimplexV
Definition: coal/narrowphase/gjk.h:54
coal::details::GJK::vertex_id_t
unsigned char vertex_id_t
Definition: coal/narrowphase/gjk.h:62
coal::details::EPA::max_iterations
size_t max_iterations
Definition: coal/narrowphase/gjk.h:353
coal::details::GJK
class for GJK algorithm
Definition: coal/narrowphase/gjk.h:53
coal::details::EPA::sv_store
std::vector< SimplexVertex > sv_store
Definition: coal/narrowphase/gjk.h:356
coal::details::GJK::current
vertex_id_t current
Definition: coal/narrowphase/gjk.h:130
coal::details::EPA::depth
CoalScalar depth
Definition: coal/narrowphase/gjk.h:347
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::details::GJK::support_hint
support_func_guess_t support_hint
Definition: coal/narrowphase/gjk.h:112
coal::details::EPA::support_hint
support_func_guess_t support_hint
Definition: coal/narrowphase/gjk.h:346
coal::details::GJK::simplex
Simplex * simplex
Definition: coal/narrowphase/gjk.h:119
initialize
bool initialize(MeshCollisionTraversalNode< BV, RelativeTransformationIsIdentity > &node, BVHModel< BV > &model1, Transform3s &tf1, BVHModel< BV > &model2, Transform3s &tf2, CollisionResult &result, bool use_refit=false, bool refit_bottomup=false)
Initialize traversal node for collision between two meshes, given the current transforms.
Definition: coal/internal/traversal_node_setup.h:467
obb.v
list v
Definition: obb.py:48
coal::details::EPA::SimplexFaceList
The simplex list of EPA is a linked list of faces. Note: EPA's linked list does not own any memory....
Definition: coal/narrowphase/gjk.h:281
coal::details::GJK::max_iterations
size_t max_iterations
Definition: coal/narrowphase/gjk.h:124
gjk
Definition: doc/gjk.py:1


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