gjk_solver_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_GJKSOLVERLIBCCD_H
39 #define FCL_NARROWPHASE_GJKSOLVERLIBCCD_H
40 
41 #include <iostream>
42 
43 #include "fcl/common/types.h"
45 
46 namespace fcl
47 {
48 
49 namespace detail
50 {
51 
53 template <typename S_>
54 struct FCL_EXPORT GJKSolver_libccd
55 {
56  using S = S_;
57 
60  template<typename Shape1, typename Shape2>
61  FCL_DEPRECATED
62  bool shapeIntersect(
63  const Shape1& s1,
64  const Transform3<S>& tf1,
65  const Shape2& s2,
66  const Transform3<S>& tf2,
67  Vector3<S>* contact_points,
68  S* penetration_depth,
69  Vector3<S>* normal) const;
70 
72  template<typename Shape1, typename Shape2>
73  bool shapeIntersect(
74  const Shape1& s1,
75  const Transform3<S>& tf1,
76  const Shape2& s2,
77  const Transform3<S>& tf2,
78  std::vector<ContactPoint<S>>* contacts = nullptr) const;
79 
81  template<typename Shape>
82  bool shapeTriangleIntersect(
83  const Shape& s,
84  const Transform3<S>& tf,
85  const Vector3<S>& P1,
86  const Vector3<S>& P2,
87  const Vector3<S>& P3,
88  Vector3<S>* contact_points = nullptr,
89  S* penetration_depth = nullptr,
90  Vector3<S>* normal = nullptr) const;
91 
93  template<typename Shape>
94  bool shapeTriangleIntersect(
95  const Shape& s,
96  const Transform3<S>& tf1,
97  const Vector3<S>& P1,
98  const Vector3<S>& P2,
99  const Vector3<S>& P3,
100  const Transform3<S>& tf2,
101  Vector3<S>* contact_points = nullptr,
102  S* penetration_depth = nullptr,
103  Vector3<S>* normal = nullptr) const;
104 
106  template<typename Shape1, typename Shape2>
107  bool shapeDistance(
108  const Shape1& s1,
109  const Transform3<S>& tf1,
110  const Shape2& s2,
111  const Transform3<S>& tf2,
112  S* dist = nullptr,
113  Vector3<S>* p1 = nullptr,
114  Vector3<S>* p2 = nullptr) const;
115 
116 
117  template<typename Shape1, typename Shape2>
118  bool shapeSignedDistance(
119  const Shape1& s1,
120  const Transform3<S>& tf1,
121  const Shape2& s2,
122  const Transform3<S>& tf2,
123  S* dist = nullptr,
124  Vector3<S>* p1 = nullptr,
125  Vector3<S>* p2 = nullptr) const;
126 
128  template<typename Shape>
129  bool shapeTriangleDistance(
130  const Shape& s,
131  const Transform3<S>& tf,
132  const Vector3<S>& P1,
133  const Vector3<S>& P2,
134  const Vector3<S>& P3,
135  S* dist = nullptr,
136  Vector3<S>* p1 = nullptr,
137  Vector3<S>* p2 = nullptr) const;
138 
140  template<typename Shape>
141  bool shapeTriangleDistance(
142  const Shape& s,
143  const Transform3<S>& tf1,
144  const Vector3<S>& P1,
145  const Vector3<S>& P2,
146  const Vector3<S>& P3,
147  const Transform3<S>& tf2,
148  S* dist = nullptr,
149  Vector3<S>* p1 = nullptr,
150  Vector3<S>* p2 = nullptr) const;
151 
154 
155  void enableCachedGuess(bool if_enable) const;
156 
157  void setCachedGuess(const Vector3<S>& guess) const;
158 
159  Vector3<S> getCachedGuess() const;
160 
163 
166 
169 
172 
173  friend
174  std::ostream& operator<<(std::ostream& out, const GJKSolver_libccd& solver) {
175  out << "GjkSolver_libccd"
176  << "\n collision_tolerance: " << solver.collision_tolerance
177  << "\n max collision iterations: " << solver.max_collision_iterations
178  << "\n distance tolerance: " << solver.distance_tolerance
179  << "\n max distance iterations: " << solver.max_distance_iterations;
180  // NOTE: Cached guesses are not supported.
181  return out;
182  }
183 
184 };
185 
188 
189 } // namespace detail
190 } // namespace fcl
191 
193 
194 #endif
fcl::detail::GJKSolver_libccd::S
S_ S
Definition: gjk_solver_libccd.h:56
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::ContactPoint
Minimal contact information returned by collision.
Definition: contact_point.h:48
types.h
fcl::detail::GJKSolver_libccd
collision and distance solver based on libccd library.
Definition: gjk_solver_libccd.h:54
fcl::detail::GJKSolver_libccd::collision_tolerance
S collision_tolerance
the threshold used in GJK algorithm to stop collision iteration
Definition: gjk_solver_libccd.h:168
fcl::detail::GJKSolver_libccd::max_collision_iterations
unsigned int max_collision_iterations
maximum number of iterations used in GJK algorithm for collision
Definition: gjk_solver_libccd.h:162
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
gjk_solver_libccd-inl.h
fcl::detail::GJKSolver_libccd::operator<<
friend std::ostream & operator<<(std::ostream &out, const GJKSolver_libccd &solver)
Definition: gjk_solver_libccd.h:174
fcl::detail::GJKSolver_libccd::distance_tolerance
S distance_tolerance
the threshold used in GJK algorithm to stop distance iteration
Definition: gjk_solver_libccd.h:171
contact_point.h
fcl::detail::GJKSolver_libccd::max_distance_iterations
unsigned int max_distance_iterations
maximum number of iterations used in GJK algorithm for distance
Definition: gjk_solver_libccd.h:165
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45


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