test_collision_func_matrix.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021. Toyota Research Institute
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 CNRS-LAAS and AIST 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 // Tests the custom sphere-box tests: distance and collision.
38 
40 
41 #include <array>
42 
43 #include <gtest/gtest.h>
44 
48 
49 namespace fcl {
50 
51 #define NODE_CASE(node) case node: \
52  out << #node; \
53  break;
54 
55 std::ostream& operator<<(std::ostream& out, const NODE_TYPE& node) {
56  switch (node) {
78  }
79  return out;
80 }
81 
82 #undef NODE_CASE
83 
84 namespace detail {
85 namespace {
86 
87 using std::array;
88 
89 /* The collision function matrix defines the function that can be used to
90  evaluate collision between two CollisionGeometry instances based on their
91  node type. In NODE_TYPE, there are nine primitive types, eight BV types, and
92  three special values (see below). We want to confirm the table satisfies the
93  following invariants:
94 
95  1 There's a function for all primitive pairs, in both orderings.
96  2 There's a function for each (BV, geometry) combination (but not
97  (geometry, BV)).
98  3 There's a function for each BV type with its *own* type.
99  4 If octomap is available, there should be functions between GEOM_OCTREE
100  and every geometry type (in both orderings), with itself, and with each
101  BV type (in both orderings).
102 
103  Primitive geometries: GEOM_BOX, GEOM_SPHERE, GEOM_ELLIPSOID, GEOM_CAPSULE,
104  GEOM_CONE, GEOM_CYLINDER, GEOM_CONVEX, GEOM_PLANE,
105  GEOM_HALFSPACE
106  BV types: BV_AABB, BV_OBB, BV_RSS, BV_kIOS, BV_OBBRSS, BV_KDOP16, BV_KDOP18,
107  BV_KDOP24
108  Special: GEOM_TRIANGLE, GEOM_OCTREE, NODE_COUNT, BV_UNKNOWN
109 
110  NODE_COUNT is merely a convenient symbol for reporting the number of enumerated
111  values. BV_UNKNOWN and GEOM_TRIANGLE are not part of the function matrix. */
112 template <typename Solver>
113 void ConfirmSupportedGeometryForSolver() {
114  const array<NODE_TYPE, 9> geoms{GEOM_BOX, GEOM_SPHERE, GEOM_ELLIPSOID,
117  const array<NODE_TYPE, 8> bvs{BV_AABB, BV_OBB, BV_RSS, BV_kIOS, BV_OBBRSS,
119 
120  const CollisionFunctionMatrix<Solver> matrix_struct;
121  const auto& matrix = matrix_struct.collision_matrix;
122 
123  // 1) Confirm a function between geom_A -> geom_B for all geometries.
124  for (const NODE_TYPE& g1 : geoms) {
125  for (const NODE_TYPE& g2 : geoms) {
126  EXPECT_NE(matrix[g1][g2], nullptr) << "(" << g1 << ", " << g2 << ")";
127  }
128  }
129 
130  // 2) and 3) There's a function for BV -> geometry and BV -> self.
131  for (const NODE_TYPE& bv : bvs) {
132  EXPECT_NE(matrix[bv][bv], nullptr) << "(" << bv << ", " << bv << ")";
133  for (const NODE_TYPE& g : geoms) {
134  EXPECT_NE(matrix[bv][g], nullptr) << "(" << bv << ", " << g << ")";
135  }
136  }
137 
138 #if FCL_HAVE_OCTOMAP
139  // 4) Octomap has functions.
140  const NODE_TYPE oct = GEOM_OCTREE;
141  EXPECT_NE(matrix[oct][oct], nullptr) << "(" << oct << ", " << oct << ")";
142  for (const NODE_TYPE& g: geoms) {
143  EXPECT_NE(matrix[oct][g], nullptr) << "(" << oct << ", " << g << ")";
144  EXPECT_NE(matrix[g][oct], nullptr) << "(" << g << ", " << oct << ")";
145  }
146  for (const NODE_TYPE& bv: bvs) {
147  EXPECT_NE(matrix[oct][bv], nullptr) << "(" << oct << ", " << bv << ")";
148  EXPECT_NE(matrix[bv][oct], nullptr) << "(" << bv << ", " << oct << ")";
149  }
150 #endif
151 }
152 
153 GTEST_TEST(CollisionFuncMatrix, LibCccdSolverSupport) {
154  ConfirmSupportedGeometryForSolver<GJKSolver_libccd<double>>();
155 }
156 
157 GTEST_TEST(CollisionFuncMatrix, IndepSolverSupport) {
158  ConfirmSupportedGeometryForSolver<GJKSolver_indep<double>>();
159 }
160 
161 } // namespace
162 } // namespace detail
163 } // namespace fcl
164 
165 //==============================================================================
166 int main(int argc, char *argv[]) {
167  ::testing::InitGoogleTest(&argc, argv);
168  return RUN_ALL_TESTS();
169 }
collision_func_matrix.h
fcl::GEOM_OCTREE
@ GEOM_OCTREE
Definition: collision_geometry.h:54
fcl::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: collision_geometry.h:54
fcl::GEOM_CONE
@ GEOM_CONE
Definition: collision_geometry.h:54
fcl::GEOM_PLANE
@ GEOM_PLANE
Definition: collision_geometry.h:54
fcl::BV_KDOP18
@ BV_KDOP18
Definition: collision_geometry.h:53
fcl::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: collision_geometry.h:54
fcl::operator<<
std::ostream & operator<<(std::ostream &out, const NODE_TYPE &node)
Definition: test_collision_func_matrix.cpp:55
NODE_CASE
#define NODE_CASE(node)
Definition: test_collision_func_matrix.cpp:51
gjk_solver_libccd.h
main
int main(int argc, char *argv[])
Definition: test_collision_func_matrix.cpp:166
fcl::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: collision_geometry.h:54
fcl::BV_KDOP24
@ BV_KDOP24
Definition: collision_geometry.h:53
fcl::BV_UNKNOWN
@ BV_UNKNOWN
Definition: collision_geometry.h:53
fcl::BV_OBB
@ BV_OBB
Definition: collision_geometry.h:53
fcl::NODE_COUNT
@ NODE_COUNT
Definition: collision_geometry.h:54
fcl::BV_KDOP16
@ BV_KDOP16
Definition: collision_geometry.h:53
fcl::GEOM_SPHERE
@ GEOM_SPHERE
Definition: collision_geometry.h:54
fcl::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: collision_geometry.h:54
fcl::GEOM_CONVEX
@ GEOM_CONVEX
Definition: collision_geometry.h:54
fcl::detail::GTEST_TEST
GTEST_TEST(FCL_GJK_EPA, faceNormalPointingOutward)
Definition: test_gjk_libccd-inl_epa.cpp:205
fcl::BV_kIOS
@ BV_kIOS
Definition: collision_geometry.h:53
gjk_solver_indep.h
fcl::GEOM_BOX
@ GEOM_BOX
Definition: collision_geometry.h:54
fcl::BV_RSS
@ BV_RSS
Definition: collision_geometry.h:53
fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_geometry.h:53
fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_geometry.h:53
fcl::BV_AABB
@ BV_AABB
Definition: collision_geometry.h:53
collision_geometry.h
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: collision_geometry.h:54


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