test_capsule.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018. 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 implementation of a capsule object.
38 
40 
41 #include <vector>
42 
43 #include <Eigen/StdVector>
44 #include <gtest/gtest.h>
45 
46 #include "eigen_matrix_compare.h"
48 
49 namespace fcl {
50 namespace {
51 
52 typedef std::pair<double, double> paird;
53 
54 std::vector<paird> get_test_sizes() {
55  return std::vector<paird>{
56  paird(2.,3.),
57  paird(20.,30.),
58  paird(3.,2.),
59  paird(30.,20.)
60  };
61 }
62 
63 template <typename S>
64 void testLocalAABBComputation(Capsule<S>& shape, S tol) {
65  shape.computeLocalAABB();
66 
67  S r = shape.radius;
68  S l = shape.lz;
69  EXPECT_NEAR(shape.aabb_radius, Vector3<S>(r, r, 0.5 * l + r).norm(), tol);
70  EXPECT_TRUE(CompareMatrices(shape.aabb_center, Vector3<S>(0, 0, 0), tol));
71 }
72 
73 template <typename S>
74 void testVolumeComputation(const Capsule<S>& shape, S tol) {
75  S r = shape.radius;
76  S l = shape.lz;
77 
78  S pi = constants<S>::pi();
79 
80  S v_cyl = pi*r*r*l; // volume of a cylinder
81  S v_sph = 4./3.*pi*r*r*r; // volume of a sphere
82  S v_cap = v_cyl + v_sph; // total volume
83 
84  EXPECT_TRUE(Eigen::internal::isApprox(shape.computeVolume(), v_cap, tol));
85 }
86 
87 template <typename S>
88 void testMomentOfInertiaComputation(const Capsule<S>& shape, S tol) {
89  S r = shape.radius;
90  S l = shape.lz;
91 
92  S pi = constants<S>::pi();
93 
94  S v_cyl = pi*r*r*l; // volume of a cylinder
95  S v_sph = S(4./3.)*pi*r*r*r; // volume of a sphere
96 
97  S Iz_cyl = S(0.5) * v_cyl * r * r; // inertia of a cylinder around z
98  S Iz_sph = S(2./5.) * v_sph * r * r; // inertia of a sphere around z
99  S Iz = Iz_cyl + Iz_sph; // total inertia around z
100 
101  // inertia of a cylinder around x
102  S Ix_cyl = v_cyl * (S(3.) * r * r + l * l) / S(12.);
103 
104  S v_hemi = v_sph / S(2.); // volume of a hemisphere
105  S com_hemi = S(3.) * r / S(8.); // CoM of a hemisphere from base
106  S Ix0_hemi = Iz_sph / S(2.); // inertia of a hemisphere around x
107  S Ixc_hemi = Ix0_hemi - v_hemi * com_hemi * com_hemi; // inertia around CoM
108  S dz = l / S(2.) + com_hemi; // CoM translation along z-axis
109  S Ix_hemi = Ixc_hemi + v_hemi * dz * dz; // translated inertia around x
110 
111  S Ix = Ix_cyl + S(2.) * Ix_hemi; // total inertia around x
112  S Iy = Ix; // total inertia around y
113 
114  Eigen::Matrix<S,3,3> I_cap;
115  I_cap << Ix, S(0.), S(0.),
116  S(0.), Iy, S(0.),
117  S(0.), S(0.), Iz;
118 
119  EXPECT_TRUE(shape.computeMomentofInertia().isApprox(I_cap, tol));
120 }
121 
122 GTEST_TEST(Capsule, LocalAABBComputation_Capsule) {
123  for (paird pair : get_test_sizes()) {
124  double rd = pair.first;
125  double ld = pair.second;
126  Capsuled capsule_d(rd, ld);
127  testLocalAABBComputation(capsule_d, 1e-15);
128 
129  float rf = static_cast<float>(pair.first);
130  float lf = static_cast<float>(pair.second);
131  Capsulef capsule_f(rf, lf);
132  testLocalAABBComputation(capsule_f, 1e-8f);
133  }
134 }
135 
136 GTEST_TEST(Capsule, Volume_Capsule) {
137  for (paird pair : get_test_sizes()) {
138  double rd = pair.first;
139  double ld = pair.second;
140  Capsuled capsule_d(rd, ld);
141  testVolumeComputation(capsule_d, 1e-15);
142 
143  float rf = static_cast<float>(pair.first);
144  float lf = static_cast<float>(pair.second);
145  Capsulef capsule_f(rf, lf);
146  testVolumeComputation(capsule_f, 1e-8f);
147  }
148 }
149 
150 GTEST_TEST(Capsule, CenterOfMass_Capsule) {
151  Eigen::Vector3d comd = Vector3d::Zero();
152  Eigen::Vector3f comf = Vector3f::Zero();
153  for (paird pair : get_test_sizes()) {
154  double rd = pair.first;
155  double ld = pair.second;
156  Capsuled capsule_d(rd, ld);
157  EXPECT_TRUE(CompareMatrices(capsule_d.computeCOM(), comd, 0.));
158 
159  float rf = static_cast<float>(pair.first);
160  float lf = static_cast<float>(pair.second);
161  Capsulef capsule_f(rf, lf);
162  EXPECT_TRUE(CompareMatrices(capsule_f.computeCOM(), comf, 0.f));
163  }
164 }
165 
166 GTEST_TEST(Capsule, MomentOfInertia_Capsule) {
167  for (paird pair : get_test_sizes()) {
168  double rd = pair.first;
169  double ld = pair.second;
170  Capsuled capsule_d(rd, ld);
171  testMomentOfInertiaComputation(capsule_d, 1e-14);
172 
173  float rf = static_cast<float>(pair.first);
174  float lf = static_cast<float>(pair.second);
175  Capsulef capsule_f(rf, lf);
176  testMomentOfInertiaComputation(capsule_f, 1e-6f);
177  }
178 }
179 
180 GTEST_TEST(Capsule, Representation) {
181  // This defines the `shape` and `code_string` variables used in the test.
183 
184  EXPECT_TRUE(detail::ValidateRepresentation(shape, code_string));
185 }
186 
187 } // namespace
188 } // namespace fcl
189 
190 //==============================================================================
191 int main(int argc, char *argv[]) {
192  ::testing::InitGoogleTest(&argc, argv);
193  return RUN_ALL_TESTS();
194 }
eigen_matrix_compare.h
fcl::CompareMatrices
::testing::AssertionResult CompareMatrices(const Eigen::MatrixBase< DerivedA > &m1, const Eigen::MatrixBase< DerivedB > &m2, double tolerance=0.0, MatrixCompareType compare_type=MatrixCompareType::absolute)
Definition: eigen_matrix_compare.h:63
fcl::detail::ValidateRepresentation
::testing::AssertionResult ValidateRepresentation(const Shape &shape, const std::string &code_string)
Definition: representation_util.h:74
EXPECT_TRUE
#define EXPECT_TRUE(args)
fcl::Capsulef
Capsule< float > Capsulef
Definition: capsule.h:96
INSTANTIATE_AND_SAVE_STRING
#define INSTANTIATE_AND_SAVE_STRING(code)
Definition: representation_util.h:58
representation_util.h
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
main
int main(int argc, char *argv[])
Definition: test_capsule.cpp:191
r
S r
Definition: test_sphere_box.cpp:171
GTEST_TEST
GTEST_TEST(DynamicAABBTreeCollisionManager, update)
Definition: test_broadphase_dynamic_AABB_tree.cpp:61
Vector3d
fcl::Vector3d Vector3d
Definition: test_broadphase_dynamic_AABB_tree.cpp:48
fcl::Vector3f
Vector3< float > Vector3f
Definition: types.h:100
capsule.h
fcl::Capsule< double >
template class FCL_EXPORT Capsule< double >
fcl::constants::pi
static constexpr S pi()
The mathematical constant pi.
Definition: constants.h:134
fcl::Capsuled
Capsule< double > Capsuled
Definition: capsule.h:97
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45


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