gjk_libccd.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_GJKLIBCCD_H
39 #define FCL_NARROWPHASE_DETAIL_GJKLIBCCD_H
40 
41 #include <ccd/ccd.h>
42 #include <ccd/quat.h>
43 #include <ccd/vec3.h>
44 
45 #include "fcl/common/unused.h"
46 
47 #include "fcl/geometry/shape/box.h"
57 
62 
63 namespace fcl
64 {
65 
66 namespace detail
67 {
68 
70 
71 using GJKSupportFunction = void (*)(const void* obj, const ccd_vec3_t* dir_, ccd_vec3_t* v);
72 using GJKCenterFunction = void (*)(const void* obj, ccd_vec3_t* c);
73 
75 template <typename S, typename T>
76 class FCL_EXPORT GJKInitializer
77 {
78 public:
80  static GJKSupportFunction getSupportFunction() { return nullptr; }
81 
83  static GJKCenterFunction getCenterFunction() { return nullptr; }
84 
88  static void* createGJKObject(const T& /* s */, const Transform3<S>& /*tf*/) { return nullptr; }
89 
91  static void deleteGJKObject(void* o) { FCL_UNUSED(o); }
92 };
93 
95 template <typename S>
96 class FCL_EXPORT GJKInitializer<S, Cylinder<S>>
97 {
98 public:
99  static GJKSupportFunction getSupportFunction();
100  static GJKCenterFunction getCenterFunction();
101  static void* createGJKObject(const Cylinder<S>& s, const Transform3<S>& tf);
102  static void deleteGJKObject(void* o);
103 };
104 
106 template <typename S>
107 class FCL_EXPORT GJKInitializer<S, Sphere<S>>
108 {
109 public:
110  static GJKSupportFunction getSupportFunction();
111  static GJKCenterFunction getCenterFunction();
112  static void* createGJKObject(const Sphere<S>& s, const Transform3<S>& tf);
113  static void deleteGJKObject(void* o);
114 };
115 
117 template <typename S>
118 class FCL_EXPORT GJKInitializer<S, Ellipsoid<S>>
119 {
120 public:
121  static GJKSupportFunction getSupportFunction();
122  static GJKCenterFunction getCenterFunction();
123  static void* createGJKObject(const Ellipsoid<S>& s, const Transform3<S>& tf);
124  static void deleteGJKObject(void* o);
125 };
126 
128 template <typename S>
129 class FCL_EXPORT GJKInitializer<S, Box<S>>
130 {
131 public:
132  static GJKSupportFunction getSupportFunction();
133  static GJKCenterFunction getCenterFunction();
134  static void* createGJKObject(const Box<S>& s, const Transform3<S>& tf);
135  static void deleteGJKObject(void* o);
136 };
137 
139 template <typename S>
140 class FCL_EXPORT GJKInitializer<S, Capsule<S>>
141 {
142 public:
143  static GJKSupportFunction getSupportFunction();
144  static GJKCenterFunction getCenterFunction();
145  static void* createGJKObject(const Capsule<S>& s, const Transform3<S>& tf);
146  static void deleteGJKObject(void* o);
147 };
148 
150 template <typename S>
151 class FCL_EXPORT GJKInitializer<S, Cone<S>>
152 {
153 public:
154  static GJKSupportFunction getSupportFunction();
155  static GJKCenterFunction getCenterFunction();
156  static void* createGJKObject(const Cone<S>& s, const Transform3<S>& tf);
157  static void deleteGJKObject(void* o);
158 };
159 
161 template <typename S>
162 class FCL_EXPORT GJKInitializer<S, Convex<S>>
163 {
164 public:
165  static GJKSupportFunction getSupportFunction();
166  static GJKCenterFunction getCenterFunction();
167  static void* createGJKObject(const Convex<S>& s, const Transform3<S>& tf);
168  static void deleteGJKObject(void* o);
169 };
170 
172 FCL_EXPORT
174 
175 FCL_EXPORT
177 
178 template <typename S>
179 FCL_EXPORT
180 void* triCreateGJKObject(const Vector3<S>& P1, const Vector3<S>& P2, const Vector3<S>& P3);
181 
182 template <typename S>
183 FCL_EXPORT
184 void* triCreateGJKObject(const Vector3<S>& P1, const Vector3<S>& P2, const Vector3<S>& P3, const Transform3<S>& tf);
185 
186 FCL_EXPORT
187 void triDeleteGJKObject(void* o);
188 
190 template <typename S>
191 FCL_EXPORT
192 bool GJKCollide(
193  void* obj1,
194  ccd_support_fn supp1,
195  ccd_center_fn cen1,
196  void* obj2,
197  ccd_support_fn supp2,
198  ccd_center_fn cen2,
199  unsigned int max_iterations,
200  S tolerance,
201  Vector3<S>* contact_points,
202  S* penetration_depth,
203  Vector3<S>* normal);
204 
223 template <typename S>
224 FCL_EXPORT
225 bool GJKDistance(void* obj1, ccd_support_fn supp1,
226  void* obj2, ccd_support_fn supp2,
227  unsigned int max_iterations, S tolerance,
228  S* dist, Vector3<S>* p1, Vector3<S>* p2);
229 
249 template <typename S>
250 FCL_EXPORT
251 bool GJKSignedDistance(void* obj1, ccd_support_fn supp1,
252  void* obj2, ccd_support_fn supp2,
253  unsigned int max_iterations, S tolerance,
254  S* dist, Vector3<S>* p1, Vector3<S>* p2);
255 
256 
257 
258 } // namespace detail
259 } // namespace fcl
260 
262 
263 #endif
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
triangle_p.h
fcl::detail::GJKInitializer::getSupportFunction
static GJKSupportFunction getSupportFunction()
Get GJK support function.
Definition: gjk_libccd.h:80
obj2
CollisionObject< S > * obj2
Definition: broadphase_SaP.h:211
fcl::detail::GJKCollide
template bool GJKCollide(void *obj1, ccd_support_fn supp1, ccd_center_fn cen1, void *obj2, ccd_support_fn supp2, ccd_center_fn cen2, unsigned int max_iterations, double tolerance, Vector3d *contact_points, double *penetration_depth, Vector3d *normal)
sphere.h
fcl::detail::triDeleteGJKObject
void triDeleteGJKObject(void *o_)
Definition: gjk_libccd-inl.h:2958
fcl::detail::triGetSupportFunction
GJKSupportFunction triGetSupportFunction()
initialize GJK Triangle
Definition: gjk_libccd-inl.h:2908
dir_
ccd_vec3_t dir_
Definition: test_gjk_libccd-inl_gjk_doSimplex2.cpp:114
fcl::Convex
A convex polytope.
Definition: convex.h:84
simplex.h
unused.h
obj1
CollisionObject< S > * obj1
Definition: broadphase_SaP.h:210
halfspace.h
fcl::detail::GJKInitializer
initialize GJK stuffs
Definition: gjk_libccd.h:76
obj
CollisionObject< S > * obj
object
Definition: broadphase_SaP.h:164
plane.h
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
box.h
cone.h
polytope.h
ellipsoid.h
gjk_libccd-inl.h
convex.h
fcl::detail::triCreateGJKObject
template void * triCreateGJKObject(const Vector3d &P1, const Vector3d &P2, const Vector3d &P3)
alloc.h
fcl::detail::GJKInitializer::getCenterFunction
static GJKCenterFunction getCenterFunction()
Get GJK center function.
Definition: gjk_libccd.h:83
fcl::detail::GJKInitializer::deleteGJKObject
static void deleteGJKObject(void *o)
Delete GJK object.
Definition: gjk_libccd.h:91
fcl::detail::GJKSupportFunction
void(*)(const void *obj, const ccd_vec3_t *dir_, ccd_vec3_t *v) GJKSupportFunction
callback function used by GJK algorithm
Definition: gjk_libccd.h:71
fcl::Cylinder
Center at zero cylinder.
Definition: cylinder.h:51
fcl::Box
Center at zero point, axis aligned box.
Definition: box.h:51
capsule.h
FCL_UNUSED
#define FCL_UNUSED(x)
Definition: unused.h:39
fcl::Sphere
Center at zero point sphere.
Definition: sphere.h:51
tolerance
S tolerance()
Definition: test_fcl_geometric_shapes.cpp:87
fcl::detail::GJKDistance
template bool GJKDistance(void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, double tolerance, double *dist, Vector3d *p1, Vector3d *p2)
fcl::detail::triGetCenterFunction
GJKCenterFunction triGetCenterFunction()
Definition: gjk_libccd-inl.h:2913
fcl::Cone
Center at zero cone.
Definition: cone.h:51
list.h
fcl::detail::GJKSignedDistance
template bool GJKSignedDistance(void *obj1, ccd_support_fn supp1, void *obj2, ccd_support_fn supp2, unsigned int max_iterations, double tolerance, double *dist, Vector3d *p1, Vector3d *p2)
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
cylinder.h
fcl::Capsule
Center at zero point capsule.
Definition: capsule.h:51
fcl::Ellipsoid
Center at zero point ellipsoid.
Definition: ellipsoid.h:51
fcl::detail::GJKInitializer::createGJKObject
static void * createGJKObject(const T &, const Transform3< S > &)
Get GJK object from a shape Notice that only local transformation is applied. Gloal transformation ar...
Definition: gjk_libccd.h:88
fcl::detail::GJKCenterFunction
void(*)(const void *obj, ccd_vec3_t *c) GJKCenterFunction
Definition: gjk_libccd.h:72


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