test_fcl_sphere_capsule.cpp
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 #include <gtest/gtest.h>
39 
40 #include "fcl/math/constants.h"
44 
45 using namespace fcl;
46 
47 template <typename S>
49 {
51 
52  Sphere<S> sphere1 (50);
53  Transform3<S> sphere1_transform;
54  sphere1_transform.translation() = (Vector3<S> (0., 0., -50));
55 
56  Capsule<S> capsule (50, 200.);
57  Transform3<S> capsule_transform(Translation3<S>(Vector3<S>(0., 0., 200)));
58 
59  EXPECT_TRUE (!solver.shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, nullptr));
60 }
61 
62 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_z)
63 {
64 // test_Sphere_Capsule_Intersect_test_separated_z<float>();
65  test_Sphere_Capsule_Intersect_test_separated_z<double>();
66 }
67 
68 template <typename S>
70 {
72 
73  Sphere<S> sphere1 (50);
74  Transform3<S> sphere1_transform;
75  sphere1_transform.translation() = (Vector3<S> (0., 0., 50));
76 
77  Capsule<S> capsule (50, 200.);
78  Transform3<S> capsule_transform(Translation3<S>(Vector3<S>(0., 0., -200)));
79 
80  EXPECT_TRUE (!solver.shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, nullptr));
81 }
82 
83 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_z_negative)
84 {
85 // test_Sphere_Capsule_Intersect_test_separated_z_negative<float>();
86  test_Sphere_Capsule_Intersect_test_separated_z_negative<double>();
87 }
88 
89 template <typename S>
91 {
93 
94  Sphere<S> sphere1 (50);
95  Transform3<S> sphere1_transform;
96  sphere1_transform.translation() = (Vector3<S> (0., 0., -50));
97 
98  Capsule<S> capsule (50, 200.);
99  Transform3<S> capsule_transform(Translation3<S>(Vector3<S>(150., 0., 0.)));
100 
101  EXPECT_TRUE (!solver.shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, nullptr));
102 }
103 
104 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_x)
105 {
106 // test_Sphere_Capsule_Intersect_test_separated_x<float>();
107  test_Sphere_Capsule_Intersect_test_separated_x<double>();
108 }
109 
110 template <typename S>
112 {
114 
115  Sphere<S> sphere1 (50);
116  Transform3<S> sphere1_transform;
117  sphere1_transform.translation() = (Vector3<S> (0., 0., -50));
118 
119  Capsule<S> capsule (50, 200.);
120  Matrix3<S> rotation(
123  * AngleAxis<S>(0.0, Vector3<S>::UnitZ()));
124 
125  Transform3<S> capsule_transform = Transform3<S>::Identity();
126  capsule_transform.linear() = rotation;
127  capsule_transform.translation() = Vector3<S>(150., 0., 0.);
128 
129  EXPECT_TRUE (!solver.shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, nullptr));
130 }
131 
132 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_capsule_rotated)
133 {
134 // test_Sphere_Capsule_Intersect_test_separated_capsule_rotated<float>();
135  test_Sphere_Capsule_Intersect_test_separated_capsule_rotated<double>();
136 }
137 
138 template <typename S>
140 {
142 
143  Sphere<S> sphere1 (50);
144  Transform3<S> sphere1_transform(Translation3<S>(Vector3<S>(0., 0., -50)));
145 
146  Capsule<S> capsule (50, 200.);
147  Transform3<S> capsule_transform(Translation3<S>(Vector3<S>(0., 0., 125)));
148 
149  std::vector<ContactPoint<S>> contacts;
150 
151  bool is_intersecting = solver.shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, &contacts);
152 
153  S penetration = contacts[0].penetration_depth;
154  Vector3<S> contact_point = contacts[0].pos;
155  Vector3<S> normal = contacts[0].normal;
156 
157  EXPECT_TRUE (is_intersecting);
158  EXPECT_TRUE (penetration == 25.);
159  EXPECT_TRUE (Vector3<S> (0., 0., 1.).isApprox(normal));
160  EXPECT_TRUE (Vector3<S> (0., 0., 0.).isApprox(contact_point));
161 }
162 
163 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_penetration_z)
164 {
165 // test_Sphere_Capsule_Intersect_test_penetration_z<float>();
166  test_Sphere_Capsule_Intersect_test_penetration_z<double>();
167 }
168 
169 template <typename S>
171 {
173 
174  Sphere<S> sphere1 (50);
175  Transform3<S> sphere1_transform = Transform3<S>::Identity();
176 
177  Capsule<S> capsule (50, 200.);
178  Matrix3<S> rotation(
181  * AngleAxis<S>(0.0, Vector3<S>::UnitZ()));
182  Transform3<S> capsule_transform = Transform3<S>::Identity();
183  capsule_transform.linear() = rotation;
184  capsule_transform.translation() = Vector3<S> (0., 50., 75);
185 
186  std::vector<ContactPoint<S>> contacts;
187 
188  bool is_intersecting = solver.shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, &contacts);
189 
190  S penetration = contacts[0].penetration_depth;
191  Vector3<S> contact_point = contacts[0].pos;
192  Vector3<S> normal = contacts[0].normal;
193 
194  EXPECT_TRUE (is_intersecting);
195  EXPECT_NEAR (25, penetration, solver.collision_tolerance);
196  EXPECT_TRUE (Vector3<S> (0., 0., 1.).isApprox(normal));
197  EXPECT_TRUE (Vector3<S> (0., 0., 50.).isApprox(contact_point, solver.collision_tolerance));
198 }
199 
200 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_penetration_z_rotated)
201 {
202 // test_Sphere_Capsule_Intersect_test_penetration_z_rotated<float>();
203  test_Sphere_Capsule_Intersect_test_penetration_z_rotated<double>();
204 }
205 
206 template <typename S>
208 {
210 
211  Sphere<S> sphere1 (50);
212  Transform3<S> sphere1_transform(Translation3<S>(Vector3<S>(0., 0., -50)));
213 
214  Capsule<S> capsule (50, 200.);
215  Transform3<S> capsule_transform(Translation3<S>(Vector3<S>(0., 0., 100)));
216 
217  S distance;
218 
219  EXPECT_TRUE (!solver.shapeDistance(sphere1, sphere1_transform, capsule, capsule_transform, &distance));
220 
221 }
222 
223 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Distance_test_collision)
224 {
225 // test_Sphere_Capsule_Distance_test_collision<float>();
226  test_Sphere_Capsule_Distance_test_collision<double>();
227 }
228 
229 template <typename S>
231 {
233 
234  Sphere<S> sphere1 (50);
235  Transform3<S> sphere1_transform(Translation3<S>(Vector3<S>(0., 0., -50)));
236 
237  Capsule<S> capsule (50, 200.);
238  Transform3<S> capsule_transform(Translation3<S>(Vector3<S>(0., 0., 175)));
239 
240  S distance = 0.;
241  Vector3<S> p1;
242  Vector3<S> p2;
243  bool is_separated = solver.shapeDistance(sphere1, sphere1_transform, capsule, capsule_transform, &distance);
244 
245  EXPECT_TRUE (is_separated);
246  EXPECT_TRUE (distance == 25.);
247 }
248 
249 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Distance_test_separated)
250 {
251 // test_Sphere_Capsule_Distance_test_separated<float>();
252  test_Sphere_Capsule_Distance_test_separated<double>();
253 }
254 
255 //==============================================================================
256 int main(int argc, char* argv[])
257 {
258  ::testing::InitGoogleTest(&argc, argv);
259  return RUN_ALL_TESTS();
260 }
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
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::distance
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
Definition: kIOS-inl.h:266
fcl::detail::GJKSolver_libccd::shapeIntersect
FCL_DEPRECATED bool shapeIntersect(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) const
intersection checking between two shapes
test_Sphere_Capsule_Intersect_test_penetration_z_rotated
void test_Sphere_Capsule_Intersect_test_penetration_z_rotated()
Definition: test_fcl_sphere_capsule.cpp:170
EXPECT_TRUE
#define EXPECT_TRUE(args)
fcl::AngleAxis
Eigen::AngleAxis< S > AngleAxis
Definition: types.h:97
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
test_Sphere_Capsule_Intersect_test_separated_z
void test_Sphere_Capsule_Intersect_test_separated_z()
Definition: test_fcl_sphere_capsule.cpp:48
fcl::Matrix3
Eigen::Matrix< S, 3, 3 > Matrix3
Definition: types.h:85
test_Sphere_Capsule_Intersect_test_penetration_z
void test_Sphere_Capsule_Intersect_test_penetration_z()
Definition: test_fcl_sphere_capsule.cpp:139
gjk_solver_libccd.h
test_Sphere_Capsule_Intersect_test_separated_z_negative
void test_Sphere_Capsule_Intersect_test_separated_z_negative()
Definition: test_fcl_sphere_capsule.cpp:69
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
test_Sphere_Capsule_Intersect_test_separated_capsule_rotated
void test_Sphere_Capsule_Intersect_test_separated_capsule_rotated()
Definition: test_fcl_sphere_capsule.cpp:111
fcl::Translation3
Eigen::Translation< S, 3 > Translation3
Definition: types.h:94
main
int main(int argc, char *argv[])
Definition: test_fcl_sphere_capsule.cpp:256
constants.h
gjk_solver_indep.h
test_Sphere_Capsule_Distance_test_collision
void test_Sphere_Capsule_Distance_test_collision()
Definition: test_fcl_sphere_capsule.cpp:207
fcl::Sphere
Center at zero point sphere.
Definition: sphere.h:51
fcl::constants
Definition: constants.h:129
fcl::detail::GJKSolver_libccd::shapeDistance
bool shapeDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *dist=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between two shapes
Definition: gjk_solver_libccd-inl.h:640
test_Sphere_Capsule_Distance_test_separated
void test_Sphere_Capsule_Distance_test_separated()
Definition: test_fcl_sphere_capsule.cpp:230
GTEST_TEST
GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_z)
Definition: test_fcl_sphere_capsule.cpp:62
test_Sphere_Capsule_Intersect_test_separated_x
void test_Sphere_Capsule_Intersect_test_separated_x()
Definition: test_fcl_sphere_capsule.cpp:90
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::Capsule< S >
collision.h


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