sphere_cylinder-inl.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Toyota Research Institute.
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 Open Source Robotics Foundation 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 FCL_NARROWPHASE_DETAIL_SPHERECYLINDER_INL_H
38 #define FCL_NARROWPHASE_DETAIL_SPHERECYLINDER_INL_H
39 
41 
42 namespace fcl {
43 namespace detail {
44 
45 extern template FCL_EXPORT bool
47  const Transform3<double>& X_FS,
48  const Cylinder<double>& cylinder,
49  const Transform3<double>& X_FC,
50  std::vector<ContactPoint<double>>* contacts);
51 
52 //==============================================================================
53 
54 extern template FCL_EXPORT bool
56  const Transform3<double>& X_FS,
57  const Cylinder<double>& cylinder,
58  const Transform3<double>& X_FC,
59  double* distance, Vector3<double>* p_FSc,
60  Vector3<double>* p_FCs);
61 
62 //==============================================================================
63 
64 // Helper function for cylinder-sphere queries. Given a cylinder defined in its
65 // canonical frame C (i.e., centered on the origin with cylinder's height axis
66 // aligned to the Cz axis) and a query point Q, determines point N, the point
67 // *inside* the cylinder nearest to Q. Note: this is *not* necessarily the
68 // nearest point on the surface of the cylinder; if Q is inside the cylinder,
69 // then the nearest point is Q itself.
70 // @param height The height of the cylinder.
71 // @param radius The radius of the cylinder.
72 // @param p_CQ The position vector from frame C's origin to the query
73 // point Q measured and expressed in frame C.
74 // @param[out] p_CN_ptr A position vector from frame C's origin to the point N
75 // measured and expressed in frame C.
76 // @returns true if the nearest point is a different point than the query point.
77 // @pre p_CN_ptr must point to a valid Vector3<S> instance.
78 template <typename S>
79 bool nearestPointInCylinder(const S& height, const S& radius,
80  const Vector3<S>& p_CQ, Vector3<S>* p_CN_ptr) {
81  assert(p_CN_ptr != nullptr);
82  Vector3<S>& p_CN = *p_CN_ptr;
83  p_CN = p_CQ;
84 
85  bool clamped = false;
86 
87  // Linearly clamp along the cylinders height axis.
88  const S half_height = height / 2;
89  if (p_CQ(2) > half_height) {
90  clamped = true;
91  p_CN(2) = half_height;
92  } else if (p_CQ(2) < -half_height) {
93  clamped = true;
94  p_CN(2) = -half_height;
95  }
96 
97  // Clamp according to the circular cross section.
98  Vector2<S> r_CQ{p_CQ(0), p_CQ(1)};
99  S squared_distance = r_CQ.dot(r_CQ);
100  if (squared_distance > radius * radius) {
101  // The query point lies outside the *circular* extent of the cylinder.
102  clamped = true;
103  r_CQ *= radius / sqrt(squared_distance);
104  p_CN(0) = r_CQ(0);
105  p_CN(1) = r_CQ(1);
106  }
107 
108  return clamped;
109 }
110 
111 //==============================================================================
112 
113 template <typename S>
114 FCL_EXPORT bool sphereCylinderIntersect(
115  const Sphere<S>& sphere, const Transform3<S>& X_FS,
116  const Cylinder<S>& cylinder, const Transform3<S>& X_FC,
117  std::vector<ContactPoint<S>>* contacts) {
118  const S& r_s = sphere.radius;
119  // Find the sphere center So (abbreviated as S) in the cylinder's frame.
120  const Transform3<S> X_CS = X_FC.inverse() * X_FS;
121  const Vector3<S> p_CS = X_CS.translation();
122 
123  // Find N, the nearest point *inside* the cylinder to the sphere center S
124  // (measure and expressed in frame C).
125  Vector3<S> p_CN;
126  bool S_is_outside = nearestPointInCylinder(cylinder.lz, cylinder.radius, p_CS,
127  &p_CN);
128 
129  // Compute the position vector from the sphere center S to the nearest point N
130  // in the cylinder frame C. If the center is inside the cylinder, this will
131  // be the zero vector.
132  const Vector3<S> p_SN_C = p_CN - p_CS;
133  const S p_SN_squared_dist = p_SN_C.squaredNorm();
134  // The nearest point to the sphere is *farther* than radius; they are *not*
135  // penetrating.
136  if (p_SN_squared_dist > r_s * r_s)
137  return false;
138 
139  // Now we know they are colliding.
140 
141  if (contacts != nullptr) {
142  // Return values have been requested.
143  S depth{0};
144  // Normal pointing from sphere into cylinder (in cylinder's frame)
145  Vector3<S> n_SC_C;
146  // Contact position (P) in the cylinder frame.
147  Vector3<S> p_CP;
148 
149  // We want to make sure that differences exceed machine precision -- we
150  // don't want normal and contact position dominated by noise. However,
151  // because we apply an arbitrary rigid transform to the sphere's center, we
152  // lose bits of precision. For an arbitrary non-identity transform, 4 bits
153  // is the maximum possible precision loss. So, we only consider a point to
154  // be outside the cylinder if it's distance is at least that epsilon.
155  // Furthermore, in finding the *near* face, a better candidate must be more
156  // than this epsilon closer to the sphere center (see the test in the
157  // else branch).
158  constexpr auto eps = 16 * constants<S>::eps();
159  if (S_is_outside && p_SN_squared_dist > eps * eps) {
160  // The sphere center is *measurably outside* the cylinder. There are three
161  // possibilities: nearest point lies on the cap face, cap edge, or barrel.
162  // In all three cases, the normal points from the nearest point to the
163  // sphere center. Penetration depth is the radius minus the distance
164  // between the pair of points. And the contact point is simply half the
165  // depth from the nearest point in the normal direction.
166 
167  // Distance from closest point (N) to sphere center (S).
168  const S d_NS = sqrt(p_SN_squared_dist);
169  n_SC_C = p_SN_C / d_NS;
170  depth = r_s - d_NS;
171  p_CP = p_CN + n_SC_C * (depth * 0.5);
172  } else {
173  // The center is inside. It's either nearer the barrel or the end face
174  // (with preference for the end face).
175  const S& h = cylinder.lz;
176  const S face_distance = p_CS(2) >= 0 ? h / 2 - p_CS(2) : p_CS(2) + h / 2;
177  // For the barrel to be picked over the face, it must be more than
178  // epsilon closer to the sphere center.
179 
180  // The direction from the sphere to the nearest point on the barrel on
181  // the z = 0 plane.
182  const Vector2<S> n_SB_xy = Vector2<S>(p_CS(0), p_CS(1));
183  const S d_CS_xy = n_SB_xy.norm();
184  const S barrel_distance = cylinder.radius - d_CS_xy;
185  // If the center is near the Voronoi boundary between the near face and
186  // the barrel, then this test would be affected by the precision loss
187  // inherent in computing p_CS. If we did a *strict* comparison, then
188  // we would get a different answer just by changing X_FC. This requires
189  // the barrel to be closer by an amount that subsumes the potential
190  // precision loss.
191  if (barrel_distance < face_distance - eps) {
192  // Closest to the barrel.
193  if (d_CS_xy > eps) {
194  // Normal towards barrel
195  n_SC_C << -n_SB_xy(0) / d_CS_xy, -n_SB_xy(1) / d_CS_xy, 0;
196  depth = r_s + barrel_distance;
197  p_CP = p_CS + n_SC_C * ((r_s - barrel_distance) / 2);
198  } else {
199  // Sphere center is on the central spine of the cylinder, as per
200  // documentation, assume we have penetration coming in from the +x
201  // direction.
202  n_SC_C = -Vector3<S>::UnitX();
203  depth = r_s + cylinder.radius;
204  p_CP = p_CS + n_SC_C * ((r_s - barrel_distance) / 2);
205  }
206  } else {
207  // Closest to the face.
208  n_SC_C << 0, 0, 0;
209  // NOTE: This sign *may* seem counter-intuitive. A center nearest the +z
210  // face produces a normal in the -z direction; this is because the
211  // normal points from the sphere and into the cylinder; and the
212  // penetration is *into* the +z face (so points in the -z direction).
213  n_SC_C(2) = p_CS(2) >= 0 ? -1 : 1;
214  depth = face_distance + r_s;
215  p_CP = p_CS + n_SC_C * ((r_s - face_distance) / 2);
216  }
217  }
218  contacts->emplace_back(X_FC.linear() * n_SC_C, X_FC * p_CP, depth);
219  }
220  return true;
221 }
222 
223 //==============================================================================
224 
225 template <typename S>
226 FCL_EXPORT bool sphereCylinderDistance(const Sphere<S>& sphere,
227  const Transform3<S>& X_FS,
228  const Cylinder<S>& cylinder,
229  const Transform3<S>& X_FC, S* distance,
230  Vector3<S>* p_FSc, Vector3<S>* p_FCs) {
231  // Find the sphere center S in the cylinder's frame.
232  const Transform3<S> X_CS = X_FC.inverse() * X_FS;
233  const Vector3<S> p_CS = X_CS.translation();
234  const S r_s = sphere.radius;
235 
236  // Find N, the nearest point *inside* the cylinder to the sphere center S
237  // (measured and expressed in frame C).
238  Vector3<S> p_CN;
239  bool S_is_outside = nearestPointInCylinder(cylinder.lz, cylinder.radius, p_CS,
240  &p_CN);
241 
242  if (S_is_outside) {
243  // If N is not S, we know the sphere center is *outside* the cylinder (but
244  // we don't know yet if the they are completely separated).
245 
246  // Compute the position vector from the nearest point N to the sphere center
247  // S in the frame C.
248  const Vector3<S> p_NS_C = p_CS - p_CN;
249  const S p_NS_squared_dist = p_NS_C.squaredNorm();
250  if (p_NS_squared_dist > r_s * r_s) {
251  // The distance to the nearest point is greater than the sphere radius;
252  // we have proven separation.
253  S d{-1};
254  if (distance || p_FCs || p_FSc)
255  d = sqrt(p_NS_squared_dist);
256  if (distance != nullptr)
257  *distance = d - r_s;
258  if (p_FCs != nullptr)
259  *p_FCs = X_FC * p_CN;
260  if (p_FSc != nullptr) {
261  const Vector3<S> p_CSc = p_CS - (p_NS_C * r_s / d);
262  *p_FSc = X_FC * p_CSc;
263  }
264  return true;
265  }
266  }
267 
268  // We didn't *prove* separation, so we must be in penetration.
269  if (distance != nullptr) *distance = -1;
270  return false;
271 }
272 
273 } // namespace detail
274 } // namespace fcl
275 
276 #endif // FCL_NARROWPHASE_DETAIL_SPHERECYLINDER_INL_H
fcl::Sphere< double >
template class FCL_EXPORT Sphere< double >
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::ContactPoint
Minimal contact information returned by collision.
Definition: contact_point.h:48
r_s
S r_s
Definition: test_sphere_cylinder.cpp:187
fcl::constants::eps
static constexpr Real eps()
Returns ε for the precision of the underlying scalar type.
Definition: constants.h:151
fcl::Vector2
Eigen::Matrix< S, 2, 1 > Vector2
Definition: types.h:67
fcl::detail::nearestPointInCylinder
bool nearestPointInCylinder(const S &height, const S &radius, const Vector3< S > &p_CQ, Vector3< S > *p_CN_ptr)
Definition: sphere_cylinder-inl.h:79
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::Sphere::radius
S radius
Radius of the sphere.
Definition: sphere.h:60
fcl::detail::distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
fcl::Cylinder
Center at zero cylinder.
Definition: cylinder.h:51
fcl::Cylinder::lz
S lz
Length along z axis.
Definition: cylinder.h:64
fcl::Sphere
Center at zero point sphere.
Definition: sphere.h:51
fcl::Cylinder< double >
template class FCL_EXPORT Cylinder< double >
fcl::detail::sphereCylinderDistance
template FCL_EXPORT bool sphereCylinderDistance(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, double *distance, Vector3< double > *p_FSc, Vector3< double > *p_FCs)
fcl::detail::sphereCylinderIntersect
template FCL_EXPORT bool sphereCylinderIntersect(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, std::vector< ContactPoint< double >> *contacts)
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
sphere_cylinder.h
fcl::Cylinder::radius
S radius
Radius of the cylinder.
Definition: cylinder.h:61


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48