narrowphase/detail/primitive_shape_algorithm/halfspace.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_HALFSPACE_H
39 #define FCL_NARROWPHASE_DETAIL_HALFSPACE_H
40 
44 #include "fcl/geometry/shape/box.h"
51 
52 namespace fcl
53 {
54 
55 namespace detail
56 {
57 
58 template <typename S>
59 FCL_EXPORT
61 
62 template <>
63 FCL_EXPORT
65 
66 template <>
67 FCL_EXPORT
69 
70 template <typename S>
71 FCL_EXPORT
72 bool sphereHalfspaceIntersect(const Sphere<S>& s1, const Transform3<S>& tf1,
73  const Halfspace<S>& s2, const Transform3<S>& tf2,
74  std::vector<ContactPoint<S>>* contacts);
75 
76 template <typename S>
77 FCL_EXPORT
78 bool ellipsoidHalfspaceIntersect(const Ellipsoid<S>& s1, const Transform3<S>& tf1,
79  const Halfspace<S>& s2, const Transform3<S>& tf2,
80  std::vector<ContactPoint<S>>* contacts);
81 
87 template <typename S>
88 FCL_EXPORT
89 bool boxHalfspaceIntersect(const Box<S>& s1, const Transform3<S>& tf1,
90  const Halfspace<S>& s2, const Transform3<S>& tf2);
91 
92 template <typename S>
93 FCL_EXPORT
94 bool boxHalfspaceIntersect(const Box<S>& s1, const Transform3<S>& tf1,
95  const Halfspace<S>& s2, const Transform3<S>& tf2,
96  std::vector<ContactPoint<S>>* contacts);
97 
98 template <typename S>
99 FCL_EXPORT
100 bool capsuleHalfspaceIntersect(const Capsule<S>& s1, const Transform3<S>& tf1,
101  const Halfspace<S>& s2, const Transform3<S>& tf2,
102  std::vector<ContactPoint<S>>* contacts);
103 
104 template <typename S>
105 FCL_EXPORT
106 bool cylinderHalfspaceIntersect(const Cylinder<S>& s1, const Transform3<S>& tf1,
107  const Halfspace<S>& s2, const Transform3<S>& tf2,
108  std::vector<ContactPoint<S>>* contacts);
109 
110 template <typename S>
111 FCL_EXPORT
112 bool coneHalfspaceIntersect(const Cone<S>& s1, const Transform3<S>& tf1,
113  const Halfspace<S>& s2, const Transform3<S>& tf2,
114  std::vector<ContactPoint<S>>* contacts);
115 
116 template <typename S>
117 FCL_EXPORT
118 bool convexHalfspaceIntersect(const Convex<S>& s1, const Transform3<S>& tf1,
119  const Halfspace<S>& s2, const Transform3<S>& tf2,
120  Vector3<S>* contact_points, S* penetration_depth, Vector3<S>* normal);
121 
162 template <typename S>
163 FCL_EXPORT bool convexHalfspaceIntersect(
164  const Convex<S>& convex_C, const Transform3<S>& X_FC,
165  const Halfspace<S>& half_space_H, const Transform3<S>& X_FH,
166  std::vector<ContactPoint<S>>* contacts);
167 
168 template <typename S>
169 FCL_EXPORT
170 bool halfspaceTriangleIntersect(const Halfspace<S>& s1, const Transform3<S>& tf1,
171  const Vector3<S>& P1, const Vector3<S>& P2, const Vector3<S>& P3, const Transform3<S>& tf2,
172  Vector3<S>* contact_points, S* penetration_depth, Vector3<S>* normal);
173 
181 template <typename S>
182 FCL_EXPORT
183 bool planeHalfspaceIntersect(const Plane<S>& s1, const Transform3<S>& tf1,
184  const Halfspace<S>& s2, const Transform3<S>& tf2,
185  Plane<S>& pl,
186  Vector3<S>& p, Vector3<S>& d,
187  S& penetration_depth,
188  int& ret);
189 
190 template <typename S>
191 FCL_EXPORT
192 bool halfspacePlaneIntersect(const Halfspace<S>& s1, const Transform3<S>& tf1,
193  const Plane<S>& s2, const Transform3<S>& tf2,
194  Plane<S>& pl, Vector3<S>& p, Vector3<S>& d,
195  S& penetration_depth,
196  int& ret);
197 
206 template <typename S>
207 FCL_EXPORT
208 bool halfspaceIntersect(const Halfspace<S>& s1, const Transform3<S>& tf1,
209  const Halfspace<S>& s2, const Transform3<S>& tf2,
210  Vector3<S>& p, Vector3<S>& d,
211  Halfspace<S>& s,
212  S& penetration_depth,
213  int& ret);
214 
215 } // namespace detail
216 } // namespace fcl
217 
219 
220 #endif
fcl::detail::halfspaceTriangleIntersect
template bool halfspaceTriangleIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
fcl::detail::cylinderHalfspaceIntersect
template bool cylinderHalfspaceIntersect(const Cylinder< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::sphereHalfspaceIntersect
template bool sphereHalfspaceIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
sphere.h
fcl::detail::planeHalfspaceIntersect
template bool planeHalfspaceIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret)
fcl::detail::capsuleHalfspaceIntersect
template bool capsuleHalfspaceIntersect(const Capsule< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
halfspace.h
plane.h
fcl::detail::convexHalfspaceIntersect
template bool convexHalfspaceIntersect(const Convex< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
box.h
cone.h
ellipsoid.h
fcl::detail::coneHalfspaceIntersect
template bool coneHalfspaceIntersect(const Cone< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
convex.h
fcl::detail::halfspaceIntersect
template bool halfspaceIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > &p, Vector3< double > &d, Halfspace< double > &s, double &penetration_depth, int &ret)
contact_point.h
fcl::detail::halfspacePlaneIntersect
template bool halfspacePlaneIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret)
fcl::detail::boxHalfspaceIntersect
template bool boxHalfspaceIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2)
capsule.h
halfspace-inl.h
fcl::detail::halfspaceIntersectTolerance
S halfspaceIntersectTolerance()
Definition: narrowphase/detail/primitive_shape_algorithm/halfspace-inl.h:148
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::detail::ellipsoidHalfspaceIntersect
template bool ellipsoidHalfspaceIntersect(const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
cylinder.h


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