test_fcl_cylinder_half_space.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Toyota Research Institute
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  * * Neither the name of Open Source Robotics Foundation nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
36 #include <iostream>
37 
38 #include <gtest/gtest.h>
39 
40 #include "fcl/fcl.h"
41 
42 using namespace std;
43 using namespace fcl;
44 
45 template <typename S>
47 {
48  // Numerical precision expected in the results.
49  const double kTolerance = 20 * std::numeric_limits<double>::epsilon();
50 
51  const S radius = 0.05;
52  const S length = 4 * radius;
53 
54  auto half_space = std::make_shared<Halfspace<S>>(Vector3<S>::UnitZ(), 0.0);
55  auto cylinder = std::make_shared<Cylinder<S>>(radius, length);
56 
57  // Pose of cylinder frame C in the world frame W.
58  Transform3<S> X_WC(Translation3<S>(Vector3<S>(0.0, 0.0, 0.049)));
59 
60  // Pose of half space frame H in the world frame W.
62 
63  CollisionObject<S> half_space_co(half_space, X_WH);
64  CollisionObject<S> cylinder_co(cylinder, X_WC);
65 
68  static const bool enable_contact = true;
70  request.gjk_solver_type = solver_type;
71 
72  fcl::collide(&half_space_co, &cylinder_co, request, result);
73  vector<Contact<S>> contacts;
74  result.getContacts(contacts);
75 
76  EXPECT_EQ(static_cast<int>(contacts.size()), 1);
77  EXPECT_NEAR(contacts[0].penetration_depth, 0.051, kTolerance);
78 
79  // Now perform the same test but with the cylinder's z axis Cz pointing down.
80  X_WC.linear() = AngleAxis<S>(fcl::constants<S>::pi(),
81  Vector3d::UnitX()).matrix();
82  X_WC.translation() = Vector3<S>(0, 0, 0.049);
83  cylinder_co.setTransform(X_WC);
84 
85  result.clear();
86  contacts.clear();
87 
88  fcl::collide(&half_space_co, &cylinder_co, request, result);
89  result.getContacts(contacts);
90 
91  EXPECT_EQ(static_cast<int>(contacts.size()), 1);
92  EXPECT_NEAR(contacts[0].penetration_depth, 0.051, kTolerance);
93 }
94 
95 GTEST_TEST(FCL_GEOMETRIC_SHAPES, collision_cylinder_half_space_libccd)
96 {
97  test_collision_cylinder_half_space<double>(fcl::GJKSolverType::GST_LIBCCD);
98 }
99 
100 GTEST_TEST(FCL_GEOMETRIC_SHAPES, collision_cylinder_half_space_indep)
101 {
102  test_collision_cylinder_half_space<double>(fcl::GJKSolverType::GST_INDEP);
103 }
104 
105 int main(int argc, char* argv[])
106 {
107  ::testing::InitGoogleTest(&argc, argv);
108  return RUN_ALL_TESTS();
109 }
fcl::CollisionObject::setTransform
void setTransform(const Matrix3< S > &R, const Vector3< S > &T)
set object's transform
Definition: collision_object-inl.h:198
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::CollisionRequest::gjk_solver_type
GJKSolverType gjk_solver_type
Enumeration indicating the GJK solver implementation to use.
Definition: collision_request.h:78
fcl::GJKSolverType
GJKSolverType
Type of narrow phase GJK solver.
Definition: gjk_solver_type.h:45
epsilon
S epsilon()
Definition: test_fcl_simple.cpp:56
main
int main(int argc, char *argv[])
Definition: test_fcl_cylinder_half_space.cpp:105
max
static T max(T x, T y)
Definition: svm.cpp:52
fcl::CollisionResult::clear
void clear()
clear the results obtained
Definition: collision_result-inl.h:125
fcl::CollisionResult
collision result
Definition: collision_request.h:48
fcl::AngleAxis
Eigen::AngleAxis< S > AngleAxis
Definition: types.h:97
test_collision_cylinder_half_space
void test_collision_cylinder_half_space(fcl::GJKSolverType solver_type)
Definition: test_fcl_cylinder_half_space.cpp:46
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
fcl::GST_LIBCCD
@ GST_LIBCCD
Definition: gjk_solver_type.h:45
fcl::CollisionRequest
Parameters for performing collision request.
Definition: collision_request.h:52
fcl::Translation3
Eigen::Translation< S, 3 > Translation3
Definition: types.h:94
fcl::collide
template FCL_EXPORT std::size_t collide(const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result)
fcl::CollisionResult::getContacts
void getContacts(std::vector< Contact< S >> &contacts_)
get all the contacts
Definition: collision_result-inl.h:107
GTEST_TEST
GTEST_TEST(FCL_GEOMETRIC_SHAPES, collision_cylinder_half_space_libccd)
Definition: test_fcl_cylinder_half_space.cpp:95
enable_contact
bool enable_contact
Definition: test_fcl_collision.cpp:75
fcl::constants
Definition: constants.h:129
fcl::GST_INDEP
@ GST_INDEP
Definition: gjk_solver_type.h:45
num_max_contacts
int num_max_contacts
Definition: test_fcl_collision.cpp:74
fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:51
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
EXPECT_EQ
#define EXPECT_EQ(a, b)


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