minkowski_diff-inl.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-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef FCL_NARROWPHASE_DETAIL_MINKOWSKIDIFF_INL_H
39 #define FCL_NARROWPHASE_DETAIL_MINKOWSKIDIFF_INL_H
40 
42 
43 #include "fcl/geometry/shape/box.h"
53 
54 namespace fcl
55 {
56 
57 namespace detail
58 {
59 
60 //==============================================================================
61 extern template
62 struct MinkowskiDiff<double>;
63 
64 //==============================================================================
65 template <typename S, typename Derived>
66 FCL_EXPORT
68  const ShapeBase<S>* shape,
69  const Eigen::MatrixBase<Derived>& dir)
70 {
71  // Check the number of rows is 6 at compile time
72  EIGEN_STATIC_ASSERT(
73  Derived::RowsAtCompileTime == 3
74  && Derived::ColsAtCompileTime == 1,
75  THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE);
76 
77  switch(shape->getNodeType())
78  {
79  case GEOM_TRIANGLE:
80  {
81  const auto* triangle = static_cast<const TriangleP<S>*>(shape);
82  S dota = dir.dot(triangle->a);
83  S dotb = dir.dot(triangle->b);
84  S dotc = dir.dot(triangle->c);
85  if(dota > dotb)
86  {
87  if(dotc > dota)
88  return triangle->c;
89  else
90  return triangle->a;
91  }
92  else
93  {
94  if(dotc > dotb)
95  return triangle->c;
96  else
97  return triangle->b;
98  }
99  }
100  break;
101  case GEOM_BOX:
102  {
103  const Box<S>* box = static_cast<const Box<S>*>(shape);
104  return Vector3<S>((dir[0]>0)?(box->side[0]/2):(-box->side[0]/2),
105  (dir[1]>0)?(box->side[1]/2):(-box->side[1]/2),
106  (dir[2]>0)?(box->side[2]/2):(-box->side[2]/2));
107  }
108  break;
109  case GEOM_SPHERE:
110  {
111  const Sphere<S>* sphere = static_cast<const Sphere<S>*>(shape);
112  return dir * sphere->radius;
113  }
114  break;
115  case GEOM_ELLIPSOID:
116  {
117  const Ellipsoid<S>* ellipsoid = static_cast<const Ellipsoid<S>*>(shape);
118 
119  const S a2 = ellipsoid->radii[0] * ellipsoid->radii[0];
120  const S b2 = ellipsoid->radii[1] * ellipsoid->radii[1];
121  const S c2 = ellipsoid->radii[2] * ellipsoid->radii[2];
122 
123  const Vector3<S> v(a2 * dir[0], b2 * dir[1], c2 * dir[2]);
124  const S d = std::sqrt(v.dot(dir));
125 
126  return v / d;
127  }
128  break;
129  case GEOM_CAPSULE:
130  {
131  const Capsule<S>* capsule = static_cast<const Capsule<S>*>(shape);
132  S half_h = capsule->lz * 0.5;
133  Vector3<S> pos1(0, 0, half_h);
134  Vector3<S> pos2(0, 0, -half_h);
135  Vector3<S> v = dir * capsule->radius;
136  pos1 += v;
137  pos2 += v;
138  if(dir.dot(pos1) > dir.dot(pos2))
139  return pos1;
140  else return pos2;
141  }
142  break;
143  case GEOM_CONE:
144  {
145  const Cone<S>* cone = static_cast<const Cone<S>*>(shape);
146  S zdist = dir[0] * dir[0] + dir[1] * dir[1];
147  S len = zdist + dir[2] * dir[2];
148  zdist = std::sqrt(zdist);
149  len = std::sqrt(len);
150  S half_h = cone->lz * 0.5;
151  S radius = cone->radius;
152 
153  S sin_a = radius / std::sqrt(radius * radius + 4 * half_h * half_h);
154 
155  if(dir[2] > len * sin_a)
156  return Vector3<S>(0, 0, half_h);
157  else if(zdist > 0)
158  {
159  S rad = radius / zdist;
160  return Vector3<S>(rad * dir[0], rad * dir[1], -half_h);
161  }
162  else
163  return Vector3<S>(0, 0, -half_h);
164  }
165  break;
166  case GEOM_CYLINDER:
167  {
168  const Cylinder<S>* cylinder = static_cast<const Cylinder<S>*>(shape);
169  S zdist = std::sqrt(dir[0] * dir[0] + dir[1] * dir[1]);
170  S half_h = cylinder->lz * 0.5;
171  if(zdist == 0.0)
172  {
173  return Vector3<S>(0, 0, (dir[2]>0)? half_h:-half_h);
174  }
175  else
176  {
177  S d = cylinder->radius / zdist;
178  return Vector3<S>(d * dir[0], d * dir[1], (dir[2]>0)?half_h:-half_h);
179  }
180  }
181  break;
182  case GEOM_CONVEX:
183  {
184  const Convex<S>* convex = static_cast<const Convex<S>*>(shape);
185  S maxdot = - std::numeric_limits<S>::max();
186  Vector3<S> bestv = Vector3<S>::Zero();
187  for(const auto& vertex : convex->getVertices())
188  {
189  S dot = dir.dot(vertex);
190  if(dot > maxdot)
191  {
192  bestv = vertex;
193  maxdot = dot;
194  }
195  }
196  return bestv;
197  }
198  break;
199  case GEOM_PLANE:
200  break;
201  default:
202  ; // nothing
203  }
204 
205  return Vector3<S>::Zero();
206 }
207 
208 //==============================================================================
209 template <typename S>
211 {
212  // Do nothing
213 }
214 
215 //==============================================================================
216 template <typename S>
218 {
219  return getSupport(shapes[0], d);
220 }
221 
222 //==============================================================================
223 template <typename S>
225 {
226  return toshape0 * getSupport(shapes[1], toshape1 * d);
227 }
228 
229 //==============================================================================
230 template <typename S>
232 {
233  return support0(d) - support1(-d);
234 }
235 
236 //==============================================================================
237 template <typename S>
238 Vector3<S> MinkowskiDiff<S>::support(const Vector3<S>& d, size_t index) const
239 {
240  if(index)
241  return support1(d);
242  else
243  return support0(d);
244 }
245 
246 //==============================================================================
247 template <typename S>
249 {
250  if(d.dot(v) <= 0)
251  return getSupport(shapes[0], d);
252  else
253  return getSupport(shapes[0], d) + v;
254 }
255 
256 //==============================================================================
257 template <typename S>
259 {
260  return support0(d, v) - support1(-d);
261 }
262 
263 //==============================================================================
264 template <typename S>
265 Vector3<S> MinkowskiDiff<S>::support(const Vector3<S>& d, const Vector3<S>& v, size_t index) const
266 {
267  if(index)
268  return support1(d);
269  else
270  return support0(d, v);
271 }
272 
273 } // namespace detail
274 } // namespace fcl
275 
276 #endif
triangle_p.h
fcl::Capsule::radius
S radius
Radius of capsule.
Definition: capsule.h:61
sphere.h
fcl::TriangleP::c
Vector3< S > c
Definition: triangle_p.h:68
fcl::Convex< S >
fcl::GEOM_CONE
@ GEOM_CONE
Definition: collision_geometry.h:54
fcl::GEOM_PLANE
@ GEOM_PLANE
Definition: collision_geometry.h:54
halfspace.h
fcl::Ellipsoid::radii
Vector3< S > radii
Radii of the ellipsoid.
Definition: ellipsoid.h:64
max
static T max(T x, T y)
Definition: svm.cpp:52
fcl::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: collision_geometry.h:54
fcl::Capsule::lz
S lz
Length along z axis.
Definition: capsule.h:64
fcl::ShapeBase< S >
fcl::detail::MinkowskiDiff::support
Vector3< S > support(const Vector3< S > &d) const
support function for the pair of shapes
Definition: minkowski_diff-inl.h:231
plane.h
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
box.h
cone.h
ellipsoid.h
fcl::CollisionGeometry::getNodeType
virtual NODE_TYPE getNodeType() const
get the node type
Definition: collision_geometry-inl.h:79
fcl::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: collision_geometry.h:54
convex.h
fcl::Cone::lz
S lz
Length along z axis.
Definition: cone.h:63
fcl::Convex::getVertices
const std::vector< Vector3< S > > & getVertices() const
Gets the vertex positions in the geometry's frame G.
Definition: convex.h:126
fcl::TriangleP
Triangle stores the points instead of only indices of points.
Definition: triangle_p.h:50
fcl::Sphere::radius
S radius
Radius of the sphere.
Definition: sphere.h:60
fcl::GEOM_SPHERE
@ GEOM_SPHERE
Definition: collision_geometry.h:54
fcl::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: collision_geometry.h:54
fcl::Cone::radius
S radius
Radius of the cone.
Definition: cone.h:60
fcl::GEOM_CONVEX
@ GEOM_CONVEX
Definition: collision_geometry.h:54
fcl::Cylinder
Center at zero cylinder.
Definition: cylinder.h:51
fcl::detail::MinkowskiDiff::support1
Vector3< S > support1(const Vector3< S > &d) const
support function for shape1
Definition: minkowski_diff-inl.h:224
minkowski_diff.h
fcl::detail::MinkowskiDiff::MinkowskiDiff
MinkowskiDiff()
Definition: minkowski_diff-inl.h:210
fcl::Box
Center at zero point, axis aligned box.
Definition: box.h:51
capsule.h
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::GEOM_BOX
@ GEOM_BOX
Definition: collision_geometry.h:54
fcl::Cone
Center at zero cone.
Definition: cone.h:51
fcl::detail::MinkowskiDiff::support0
Vector3< S > support0(const Vector3< S > &d) const
support function for shape0
Definition: minkowski_diff-inl.h:217
fcl::detail::getSupport
FCL_EXPORT Vector3< S > getSupport(const ShapeBase< S > *shape, const Eigen::MatrixBase< Derived > &dir)
the support function for shape
Definition: minkowski_diff-inl.h:67
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: collision_geometry.h:54
cylinder.h
fcl::Box::side
Vector3< S > side
box side length
Definition: box.h:67
fcl::Capsule< S >
fcl::Ellipsoid
Center at zero point ellipsoid.
Definition: ellipsoid.h:51
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