43 #include <Eigen/StdVector>
44 #include <gtest/gtest.h>
52 typedef std::pair<double, double> paird;
54 std::vector<paird> get_test_sizes() {
55 return std::vector<paird>{
64 void testLocalAABBComputation(Capsule<S>& shape, S tol) {
65 shape.computeLocalAABB();
69 EXPECT_NEAR(shape.aabb_radius, Vector3<S>(
r,
r, 0.5 * l +
r).norm(), tol);
74 void testVolumeComputation(
const Capsule<S>& shape, S tol) {
81 S v_sph = 4./3.*pi*
r*
r*
r;
82 S v_cap = v_cyl + v_sph;
84 EXPECT_TRUE(Eigen::internal::isApprox(shape.computeVolume(), v_cap, tol));
88 void testMomentOfInertiaComputation(
const Capsule<S>& shape, S tol) {
95 S v_sph = S(4./3.)*pi*
r*
r*
r;
97 S Iz_cyl = S(0.5) * v_cyl *
r *
r;
98 S Iz_sph = S(2./5.) * v_sph *
r *
r;
99 S Iz = Iz_cyl + Iz_sph;
102 S Ix_cyl = v_cyl * (S(3.) *
r *
r + l * l) / S(12.);
104 S v_hemi = v_sph / S(2.);
105 S com_hemi = S(3.) *
r / S(8.);
106 S Ix0_hemi = Iz_sph / S(2.);
107 S Ixc_hemi = Ix0_hemi - v_hemi * com_hemi * com_hemi;
108 S dz = l / S(2.) + com_hemi;
109 S Ix_hemi = Ixc_hemi + v_hemi * dz * dz;
111 S Ix = Ix_cyl + S(2.) * Ix_hemi;
114 Eigen::Matrix<S,3,3> I_cap;
115 I_cap << Ix, S(0.), S(0.),
119 EXPECT_TRUE(shape.computeMomentofInertia().isApprox(I_cap, tol));
122 GTEST_TEST(Capsule, LocalAABBComputation_Capsule) {
123 for (paird pair : get_test_sizes()) {
124 double rd = pair.first;
125 double ld = pair.second;
127 testLocalAABBComputation(capsule_d, 1e-15);
129 float rf =
static_cast<float>(pair.first);
130 float lf =
static_cast<float>(pair.second);
132 testLocalAABBComputation(capsule_f, 1e-8f);
137 for (paird pair : get_test_sizes()) {
138 double rd = pair.first;
139 double ld = pair.second;
141 testVolumeComputation(capsule_d, 1e-15);
143 float rf =
static_cast<float>(pair.first);
144 float lf =
static_cast<float>(pair.second);
146 testVolumeComputation(capsule_f, 1e-8f);
153 for (paird pair : get_test_sizes()) {
154 double rd = pair.first;
155 double ld = pair.second;
159 float rf =
static_cast<float>(pair.first);
160 float lf =
static_cast<float>(pair.second);
166 GTEST_TEST(Capsule, MomentOfInertia_Capsule) {
167 for (paird pair : get_test_sizes()) {
168 double rd = pair.first;
169 double ld = pair.second;
171 testMomentOfInertiaComputation(capsule_d, 1e-14);
173 float rf =
static_cast<float>(pair.first);
174 float lf =
static_cast<float>(pair.second);
176 testMomentOfInertiaComputation(capsule_f, 1e-6f);
191 int main(
int argc,
char *argv[]) {
192 ::testing::InitGoogleTest(&argc, argv);
193 return RUN_ALL_TESTS();