coal/narrowphase/support_functions.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_SUPPORT_FUNCTIONS_H
40 #define COAL_SUPPORT_FUNCTIONS_H
41 
43 #include "coal/math/transform.h"
44 #include "coal/collision_data.h"
45 
46 namespace coal {
47 
48 namespace details {
49 
61 };
62 
63 // ============================================================================
64 // ============================ SUPPORT FUNCTIONS =============================
65 // ============================================================================
76 template <int _SupportOptions = SupportOptions::NoSweptSphere>
77 Vec3s getSupport(const ShapeBase* shape, const Vec3s& dir, int& hint);
78 
80 struct COAL_DLLAPI ShapeSupportData {
81  // @brief Tracks which points have been visited in a ConvexBase.
82  std::vector<int8_t> visited;
83 
84  // @brief Tracks the last support direction used on this shape; used to
85  // warm-start the ConvexBase support function.
86  Vec3s last_dir = Vec3s::Zero();
87 
88  // @brief Temporary set used to compute the convex-hull of a support set.
89  // Only used for ConvexBase and Box.
91 };
92 
94 template <int _SupportOptions = SupportOptions::NoSweptSphere>
95 void getShapeSupport(const TriangleP* triangle, const Vec3s& dir,
96  Vec3s& support, int& /*unused*/,
97  ShapeSupportData& /*unused*/);
98 
100 template <int _SupportOptions = SupportOptions::NoSweptSphere>
101 void getShapeSupport(const Box* box, const Vec3s& dir, Vec3s& support,
102  int& /*unused*/, ShapeSupportData& /*unused*/);
103 
105 template <int _SupportOptions = SupportOptions::NoSweptSphere>
106 void getShapeSupport(const Sphere* sphere, const Vec3s& dir, Vec3s& support,
107  int& /*unused*/, ShapeSupportData& /*unused*/);
108 
110 template <int _SupportOptions = SupportOptions::NoSweptSphere>
111 void getShapeSupport(const Ellipsoid* ellipsoid, const Vec3s& dir,
112  Vec3s& support, int& /*unused*/,
113  ShapeSupportData& /*unused*/);
114 
116 template <int _SupportOptions = SupportOptions::NoSweptSphere>
117 void getShapeSupport(const Capsule* capsule, const Vec3s& dir, Vec3s& support,
118  int& /*unused*/, ShapeSupportData& /*unused*/);
119 
121 template <int _SupportOptions = SupportOptions::NoSweptSphere>
122 void getShapeSupport(const Cone* cone, const Vec3s& dir, Vec3s& support,
123  int& /*unused*/, ShapeSupportData& /*unused*/);
124 
126 template <int _SupportOptions = SupportOptions::NoSweptSphere>
127 void getShapeSupport(const Cylinder* cylinder, const Vec3s& dir, Vec3s& support,
128  int& /*unused*/, ShapeSupportData& /*unused*/);
129 
133 template <int _SupportOptions = SupportOptions::NoSweptSphere>
134 void getShapeSupport(const ConvexBase* convex, const Vec3s& dir, Vec3s& support,
135  int& hint, ShapeSupportData& /*unused*/);
136 
142 struct LargeConvex : ShapeBase {};
144 struct SmallConvex : ShapeBase {};
145 
147 template <int _SupportOptions = SupportOptions::NoSweptSphere>
148 void getShapeSupport(const SmallConvex* convex, const Vec3s& dir,
149  Vec3s& support, int& hint, ShapeSupportData& data);
150 
152 template <int _SupportOptions = SupportOptions::NoSweptSphere>
153 void getShapeSupport(const LargeConvex* convex, const Vec3s& dir,
154  Vec3s& support, int& hint, ShapeSupportData& support_data);
155 
156 // ============================================================================
157 // ========================== SUPPORT SET FUNCTIONS ===========================
158 // ============================================================================
194 template <int _SupportOptions = SupportOptions::NoSweptSphere>
195 void getSupportSet(const ShapeBase* shape, SupportSet& support_set, int& hint,
196  size_t num_sampled_supports = 6, CoalScalar tol = 1e-3);
197 
205 template <int _SupportOptions = SupportOptions::NoSweptSphere>
206 void getSupportSet(const ShapeBase* shape, const Vec3s& dir,
207  SupportSet& support_set, int& hint,
208  size_t num_sampled_supports = 6, CoalScalar tol = 1e-3) {
209  support_set.tf.rotation() = constructOrthonormalBasisFromVector(dir);
210  const Vec3s& support_dir = support_set.getNormal();
211  const Vec3s support = getSupport<_SupportOptions>(shape, support_dir, hint);
212  getSupportSet<_SupportOptions>(shape, support_set, hint, num_sampled_supports,
213  tol);
214 }
215 
218 template <int _SupportOptions = SupportOptions::NoSweptSphere>
219 void getShapeSupportSet(const TriangleP* triangle, SupportSet& support_set,
220  int& /*unused*/, ShapeSupportData& /*unused*/,
221  size_t /*unused*/ num_sampled_supports = 6,
222  CoalScalar tol = 1e-3);
223 
226 template <int _SupportOptions = SupportOptions::NoSweptSphere>
227 void getShapeSupportSet(const Box* box, SupportSet& support_set,
228  int& /*unused*/, ShapeSupportData& support_data,
229  size_t /*unused*/ num_sampled_supports = 6,
230  CoalScalar tol = 1e-3);
231 
234 template <int _SupportOptions = SupportOptions::NoSweptSphere>
235 void getShapeSupportSet(const Sphere* sphere, SupportSet& support_set,
236  int& /*unused*/, ShapeSupportData& /*unused*/,
237  size_t /*unused*/ num_sampled_supports = 6,
238  CoalScalar /*unused*/ tol = 1e-3);
239 
242 template <int _SupportOptions = SupportOptions::NoSweptSphere>
243 void getShapeSupportSet(const Ellipsoid* ellipsoid, SupportSet& support_set,
244  int& /*unused*/, ShapeSupportData& /*unused*/,
245  size_t /*unused*/ num_sampled_supports = 6,
246  CoalScalar /*unused*/ tol = 1e-3);
247 
250 template <int _SupportOptions = SupportOptions::NoSweptSphere>
251 void getShapeSupportSet(const Capsule* capsule, SupportSet& support_set,
252  int& /*unused*/, ShapeSupportData& /*unused*/,
253  size_t /*unused*/ num_sampled_supports = 6,
254  CoalScalar tol = 1e-3);
255 
258 template <int _SupportOptions = SupportOptions::NoSweptSphere>
259 void getShapeSupportSet(const Cone* cone, SupportSet& support_set,
260  int& /*unused*/, ShapeSupportData& /*unused*/,
261  size_t num_sampled_supports = 6, CoalScalar tol = 1e-3);
262 
265 template <int _SupportOptions = SupportOptions::NoSweptSphere>
266 void getShapeSupportSet(const Cylinder* cylinder, SupportSet& support_set,
267  int& /*unused*/, ShapeSupportData& /*unused*/,
268  size_t num_sampled_supports = 6, CoalScalar tol = 1e-3);
269 
274 template <int _SupportOptions = SupportOptions::NoSweptSphere>
275 void getShapeSupportSet(const ConvexBase* convex, SupportSet& support_set,
276  int& hint, ShapeSupportData& support_data,
277  size_t /*unused*/ num_sampled_supports = 6,
278  CoalScalar tol = 1e-3);
279 
282 template <int _SupportOptions = SupportOptions::NoSweptSphere>
283 void getShapeSupportSet(const SmallConvex* convex, SupportSet& support_set,
284  int& /*unused*/, ShapeSupportData& /*unused*/,
285  size_t /*unused*/ num_sampled_supports = 6,
286  CoalScalar tol = 1e-3);
287 
290 template <int _SupportOptions = SupportOptions::NoSweptSphere>
291 void getShapeSupportSet(const LargeConvex* convex, SupportSet& support_set,
292  int& hint, ShapeSupportData& support_data,
293  size_t /*unused*/ num_sampled_supports = 6,
294  CoalScalar tol = 1e-3);
295 
301 COAL_DLLAPI void computeSupportSetConvexHull(SupportSet::Polygon& cloud,
302  SupportSet::Polygon& cvx_hull);
303 
304 } // namespace details
305 
306 } // namespace coal
307 
308 #endif // COAL_SUPPORT_FUNCTIONS_H
coal::ContactPatch::Polygon
std::vector< Vec2s > Polygon
Definition: coal/collision_data.h:514
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::details::getShapeSupport
void getShapeSupport(const TriangleP *triangle, const Vec3s &dir, Vec3s &support, int &, ShapeSupportData &)
Triangle support function.
Definition: support_functions.cpp:109
collision_manager.box
box
Definition: collision_manager.py:11
coal::details::ShapeSupportData
Stores temporary data for the computation of support points.
Definition: coal/narrowphase/support_functions.h:80
coal::ContactPatch::getNormal
Vec3s getNormal() const
Normal of the contact patch, expressed in the WORLD frame.
Definition: coal/collision_data.h:569
collision_manager.sphere
sphere
Definition: collision_manager.py:4
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
collision_data.h
coal::details::ShapeSupportData::visited
std::vector< int8_t > visited
Definition: coal/narrowphase/support_functions.h:82
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::details::NoSweptSphere
@ NoSweptSphere
Definition: coal/narrowphase/support_functions.h:59
coal::Ellipsoid
Ellipsoid centered at point zero.
Definition: coal/shape/geometric_shapes.h:305
coal::details::WithSweptSphere
@ WithSweptSphere
Definition: coal/narrowphase/support_functions.h:60
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::Box
Center at zero point, axis aligned box.
Definition: coal/shape/geometric_shapes.h:166
coal::Sphere
Center at zero point sphere.
Definition: coal/shape/geometric_shapes.h:240
coal::details::getSupport
Vec3s getSupport(const ShapeBase *shape, const Vec3s &dir, int &hint)
the support function for shape. The output support point is expressed in the local frame of the shape...
Definition: support_functions.cpp:51
transform.h
coal::ShapeBase
Base class for all basic geometric shapes.
Definition: coal/shape/geometric_shapes.h:58
coal::details::ShapeSupportData::polygon
SupportSet::Polygon polygon
Definition: coal/narrowphase/support_functions.h:90
coal::details::computeSupportSetConvexHull
COAL_DLLAPI void computeSupportSetConvexHull(SupportSet::Polygon &cloud, SupportSet::Polygon &cvx_hull)
Computes the convex-hull of support_set. For now, this function is only needed for Box and ConvexBase...
Definition: support_functions.cpp:952
coal::Transform3s::rotation
const Matrix3s & rotation() const
get rotation
Definition: coal/math/transform.h:113
coal::Cylinder
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition: coal/shape/geometric_shapes.h:560
coal::ContactPatch::tf
Transform3s tf
Frame of the set, expressed in the world coordinates. The z-axis of the frame's rotation is the conta...
Definition: coal/collision_data.h:518
coal::TriangleP
Triangle stores the points instead of only indices of points.
Definition: coal/shape/geometric_shapes.h:110
coal::details::getSupportSet
void getSupportSet(const ShapeBase *shape, SupportSet &support_set, int &hint, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
Computes the support set for shape. This function assumes the frame of the support set has already be...
Definition: support_functions.cpp:450
coal::Cone
Cone The base of the cone is at and the top is at .
Definition: coal/shape/geometric_shapes.h:467
coal::details::LargeConvex
Cast a ConvexBase to a LargeConvex to use the log version of getShapeSupport. This is much faster tha...
Definition: coal/narrowphase/support_functions.h:142
coal::details::getShapeSupportSet
void getShapeSupportSet(const TriangleP *triangle, SupportSet &support_set, int &, ShapeSupportData &, size_t num_sampled_supports=6, CoalScalar tol=1e-3)
Triangle support set function. Assumes the support set frame has already been computed.
Definition: support_functions.cpp:505
coal::details::SmallConvex
See LargeConvex.
Definition: coal/narrowphase/support_functions.h:144
coal::constructOrthonormalBasisFromVector
Matrix3s constructOrthonormalBasisFromVector(const Vec3s &vec)
Construct othonormal basis from vector. The z-axis is the normalized input vector.
Definition: coal/math/transform.h:262
geometric_shapes.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::details::SupportOptions
SupportOptions
Options for the computation of support points. NoSweptSphere option is used when the support function...
Definition: coal/narrowphase/support_functions.h:58
coal::ConvexBase
Base for convex polytope.
Definition: coal/shape/geometric_shapes.h:645


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