shape_shape_func.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, CNRS-LAAS
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 Willow Garage, Inc. 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 HPP_FCL_INTERNAL_SHAPE_SHAPE_FUNC_H
38 #define HPP_FCL_INTERNAL_SHAPE_SHAPE_FUNC_H
39 
41 
42 #include <hpp/fcl/collision_data.h>
46 
47 namespace hpp {
48 namespace fcl {
49 
50 template <typename T_SH1, typename T_SH2>
51 HPP_FCL_DLLAPI FCL_REAL ShapeShapeDistance(const CollisionGeometry* o1,
52  const Transform3f& tf1,
53  const CollisionGeometry* o2,
54  const Transform3f& tf2,
55  const GJKSolver* nsolver,
56  const DistanceRequest& request,
57  DistanceResult& result);
58 
59 template <typename T_SH1, typename T_SH2>
60 struct ShapeShapeCollider {
61  static std::size_t run(const CollisionGeometry* o1, const Transform3f& tf1,
62  const CollisionGeometry* o2, const Transform3f& tf2,
63  const GJKSolver* nsolver,
64  const CollisionRequest& request,
65  CollisionResult& result) {
66  if (request.isSatisfied(result)) return result.numContacts();
67 
68  DistanceResult distanceResult;
69  DistanceRequest distanceRequest(request.enable_contact);
70  FCL_REAL distance = ShapeShapeDistance<T_SH1, T_SH2>(
71  o1, tf1, o2, tf2, nsolver, distanceRequest, distanceResult);
72 
73  size_t num_contacts = 0;
74  const Vec3f& p1 = distanceResult.nearest_points[0];
75  const Vec3f& p2 = distanceResult.nearest_points[1];
76  FCL_REAL distToCollision = distance - request.security_margin;
77 
78  internal::updateDistanceLowerBoundFromLeaf(request, result, distToCollision,
79  p1, p2);
80  if (distToCollision <= request.collision_distance_threshold &&
81  result.numContacts() < request.num_max_contacts) {
82  if (result.numContacts() < request.num_max_contacts) {
83  const Vec3f& p1 = distanceResult.nearest_points[0];
84  const Vec3f& p2 = distanceResult.nearest_points[1];
85 
86  Contact contact(
87  o1, o2, distanceResult.b1, distanceResult.b2, (p1 + p2) / 2,
88  (distance <= 0 ? distanceResult.normal : (p2 - p1).normalized()),
89  -distance);
90 
91  result.addContact(contact);
92  }
93  num_contacts = result.numContacts();
94  }
95 
96  return num_contacts;
97  }
98 };
99 
100 template <typename ShapeType1, typename ShapeType2>
101 std::size_t ShapeShapeCollide(const CollisionGeometry* o1,
102  const Transform3f& tf1,
103  const CollisionGeometry* o2,
104  const Transform3f& tf2, const GJKSolver* nsolver,
105  const CollisionRequest& request,
106  CollisionResult& result) {
108  o1, tf1, o2, tf2, nsolver, request, result);
109 }
110 
111 #define SHAPE_SHAPE_DISTANCE_SPECIALIZATION(T1, T2) \
112  template <> \
113  HPP_FCL_DLLAPI FCL_REAL ShapeShapeDistance<T1, T2>( \
114  const CollisionGeometry* o1, const Transform3f& tf1, \
115  const CollisionGeometry* o2, const Transform3f& tf2, \
116  const GJKSolver* nsolver, const DistanceRequest& request, \
117  DistanceResult& result); \
118  template <> \
119  HPP_FCL_DLLAPI FCL_REAL ShapeShapeDistance<T2, T1>( \
120  const CollisionGeometry* o1, const Transform3f& tf1, \
121  const CollisionGeometry* o2, const Transform3f& tf2, \
122  const GJKSolver* nsolver, const DistanceRequest& request, \
123  DistanceResult& result)
124 
125 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Box, Halfspace);
126 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Box, Plane);
127 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Box, Sphere);
128 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Capsule, Capsule);
129 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Capsule, Halfspace);
130 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Capsule, Plane);
131 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Cone, Halfspace);
132 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Cone, Plane);
133 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Cylinder, Halfspace);
134 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Cylinder, Plane);
135 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Sphere, Halfspace);
136 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Sphere, Plane);
137 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Sphere, Sphere);
138 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(Sphere, Cylinder);
139 
140 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(ConvexBase, Halfspace);
141 SHAPE_SHAPE_DISTANCE_SPECIALIZATION(TriangleP, Halfspace);
142 
143 #undef SHAPE_SHAPE_DISTANCE_SPECIALIZATION
144 
145 #define SHAPE_SHAPE_COLLIDE_SPECIALIZATION(T1, T2) \
146  template <> \
147  struct ShapeShapeCollider<T1, T2> { \
148  static HPP_FCL_DLLAPI std::size_t run(const CollisionGeometry* o1, \
149  const Transform3f& tf1, \
150  const CollisionGeometry* o2, \
151  const Transform3f& tf2, \
152  const GJKSolver* nsolver, \
153  const CollisionRequest& request, \
154  CollisionResult& result); \
155  }
156 
157 SHAPE_SHAPE_COLLIDE_SPECIALIZATION(Sphere, Sphere);
158 
159 #undef SHAPE_SHAPE_COLLIDE_SPECIALIZATION
160 } // namespace fcl
161 
162 } // namespace hpp
163 
165 
166 #endif
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::internal::updateDistanceLowerBoundFromLeaf
void updateDistanceLowerBoundFromLeaf(const CollisionRequest &, CollisionResult &res, const FCL_REAL &distance, const Vec3f &p0, const Vec3f &p1)
Definition: collision_data.h:547
gjk.tf1
tuple tf1
Definition: test/scripts/gjk.py:27
hpp::fcl::ShapeShapeDistance
FCL_REAL ShapeShapeDistance(const CollisionGeometry *o1, const Transform3f &tf1, const CollisionGeometry *o2, const Transform3f &tf2, const GJKSolver *nsolver, const DistanceRequest &request, DistanceResult &result)
Definition: distance_func_matrix.cpp:70
hpp::fcl::distance
HPP_FCL_DLLAPI FCL_REAL distance(const Matrix3f &R0, const Vec3f &T0, const kIOS &b1, const kIOS &b2, Vec3f *P=NULL, Vec3f *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS.cpp:181
narrowphase.h
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
collision_data.h
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
gjk.tf2
tuple tf2
Definition: test/scripts/gjk.py:36
omniidl_be_python_with_docstring.run
def run(tree, args)
Definition: omniidl_be_python_with_docstring.py:140
octree.p1
tuple p1
Definition: octree.py:54
geometric_shapes_traits.h
collision_utility.h


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:15