src/distance/capsule_capsule.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  * Copyright (c) 2015-2021, CNRS-LAAS INRIA
4  * All rights reserved.
5  *
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 Open Source Robotics Foundation 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 
34 #include "coal/math/transform.h"
37 
38 // Note that partial specialization of template functions is not allowed.
39 // Therefore, two implementations with the default narrow phase solvers are
40 // provided. If another narrow phase solver were to be used, the default
41 // template implementation would be called, unless the function is also
42 // specialized for this new type.
43 //
44 // One solution would be to make narrow phase solvers derive from an abstract
45 // class and specialize the template for this abstract class.
46 namespace coal {
47 struct GJKSolver;
48 
49 namespace internal {
51 CoalScalar clamp(const CoalScalar& num, const CoalScalar& denom) {
52  assert(denom >= 0.);
53  if (num <= 0.)
54  return 0.;
55  else if (num >= denom)
56  return 1.;
57  else
58  return num / denom;
59 }
60 
62 void clamped_linear(Vec3s& a_sd, const Vec3s& a, const CoalScalar& s_n,
63  const CoalScalar& s_d, const Vec3s& d) {
64  assert(s_d >= 0.);
65  if (s_n <= 0.)
66  a_sd = a;
67  else if (s_n >= s_d)
68  a_sd = a + d;
69  else
70  a_sd = a + s_n / s_d * d;
71 }
72 
73 // Compute the distance between C1 and C2 by computing the distance
74 // between the two segments supporting the capsules.
75 // Match algorithm of Real-Time Collision Detection, Christer Ericson - Closest
76 // Point of Two Line Segments
79 template <>
81  const CollisionGeometry* o1, const Transform3s& tf1,
82  const CollisionGeometry* o2, const Transform3s& tf2, const GJKSolver*,
83  const bool, Vec3s& wp1, Vec3s& wp2, Vec3s& normal) {
84  const Capsule* capsule1 = static_cast<const Capsule*>(o1);
85  const Capsule* capsule2 = static_cast<const Capsule*>(o2);
86 
88 
89  // We assume that capsules are centered at the origin.
90  const coal::Vec3s& c1 = tf1.getTranslation();
91  const coal::Vec3s& c2 = tf2.getTranslation();
92  // We assume that capsules are oriented along z-axis.
93  CoalScalar halfLength1 = capsule1->halfLength;
94  CoalScalar halfLength2 = capsule2->halfLength;
95  CoalScalar radius1 = (capsule1->radius + capsule1->getSweptSphereRadius());
96  CoalScalar radius2 = (capsule2->radius + capsule2->getSweptSphereRadius());
97  // direction of capsules
98  // ||d1|| = 2 * halfLength1
99  const coal::Vec3s d1 = 2 * halfLength1 * tf1.getRotation().col(2);
100  const coal::Vec3s d2 = 2 * halfLength2 * tf2.getRotation().col(2);
101 
102  // Starting point of the segments
103  // p1 + d1 is the end point of the segment
104  const coal::Vec3s p1 = c1 - d1 / 2;
105  const coal::Vec3s p2 = c2 - d2 / 2;
106  const coal::Vec3s r = p1 - p2;
107  CoalScalar a = d1.dot(d1);
108  CoalScalar b = d1.dot(d2);
109  CoalScalar c = d1.dot(r);
110  CoalScalar e = d2.dot(d2);
111  CoalScalar f = d2.dot(r);
112  // S1 is parametrized by the equation p1 + s * d1
113  // S2 is parametrized by the equation p2 + t * d2
114 
115  Vec3s w1, w2;
116  if (a <= EPSILON) {
117  w1 = p1;
118  if (e <= EPSILON)
119  // Check if the segments degenerate into points
120  w2 = p2;
121  else
122  // First segment is degenerated
123  clamped_linear(w2, p2, f, e, d2);
124  } else if (e <= EPSILON) {
125  // Second segment is degenerated
126  clamped_linear(w1, p1, -c, a, d1);
127  w2 = p2;
128  } else {
129  // Always non-negative, equal 0 if the segments are colinear
130  CoalScalar denom = fmax(a * e - b * b, 0);
131 
132  CoalScalar s;
133  CoalScalar t;
134  if (denom > EPSILON) {
135  s = clamp((b * f - c * e), denom);
136  t = b * s + f;
137  } else {
138  s = 0.;
139  t = f;
140  }
141 
142  if (t <= 0.0) {
143  w2 = p2;
144  clamped_linear(w1, p1, -c, a, d1);
145  } else if (t >= e) {
146  clamped_linear(w1, p1, (b - c), a, d1);
147  w2 = p2 + d2;
148  } else {
149  w1 = p1 + s * d1;
150  w2 = p2 + t / e * d2;
151  }
152  }
153 
154  // witness points achieving the distance between the two segments
155  CoalScalar distance = (w1 - w2).norm();
156 
157  // capsule spcecific distance computation
158  distance = distance - (radius1 + radius2);
159 
160  // Normal points from o1 to o2
161  normal = (w2 - w1).normalized();
162  wp1 = w1 + radius1 * normal;
163  wp2 = w2 - radius2 * normal;
164 
165  return distance;
166 }
167 } // namespace internal
168 
169 } // namespace coal
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
geometric_shapes.d1
float d1
Definition: scripts/geometric_shapes.py:31
coal::Capsule::halfLength
CoalScalar halfLength
Half Length along z axis.
Definition: coal/shape/geometric_shapes.h:402
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
coal::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: coal/shape/geometric_shapes.h:383
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::internal::clamp
CoalScalar clamp(const CoalScalar &num, const CoalScalar &denom)
Clamp num / denom in [0, 1].
Definition: src/distance/capsule_capsule.cpp:51
octree.r
r
Definition: octree.py:9
coal::GJKSolver
collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were imple...
Definition: coal/narrowphase/narrowphase.h:57
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::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
a
list a
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
shape_shape_func.h
transform.h
d
d
c
c
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
octree.p1
tuple p1
Definition: octree.py:54
coal::ShapeBase::getSweptSphereRadius
CoalScalar getSweptSphereRadius() const
Get radius of sphere swept around the shape. This radius is always >= 0.
Definition: coal/shape/geometric_shapes.h:86
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
epsilon
static CoalScalar epsilon
Definition: simple.cpp:12
coal::internal::clamped_linear
void clamped_linear(Vec3s &a_sd, const Vec3s &a, const CoalScalar &s_n, const CoalScalar &s_d, const Vec3s &d)
Clamp s=s_n/s_d in [0, 1] and stores a + s * d in a_sd.
Definition: src/distance/capsule_capsule.cpp:62
coal::internal::ShapeShapeDistance< Capsule, Capsule >
CoalScalar ShapeShapeDistance< Capsule, Capsule >(const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *, const bool, Vec3s &wp1, Vec3s &wp2, Vec3s &normal)
Definition: src/distance/capsule_capsule.cpp:80
coal::Capsule::radius
CoalScalar radius
Radius of capsule.
Definition: coal/shape/geometric_shapes.h:396
geometric_shapes.h
c2
c2
t
dictionary t
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76


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