test_fcl_constant_eps.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 Open Source Robotics Foundation 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 #include "fcl/math/constants.h"
38 
39 #include <cmath>
40 #include <limits>
41 
42 #include <gtest/gtest.h>
43 #include <unsupported/Eigen/AutoDiff>
44 
45 namespace fcl {
46 namespace {
47 
48 // Some autodiff helpers
49 template <typename S>
50 using Vector2 = Eigen::Matrix<S, 2, 1>;
51 template <typename S>
52 using AutoDiff2 = Eigen::AutoDiffScalar<Vector2<S>>;
53 
54 // Utility function for confirming that the value returned by `constants` is
55 // the expected value based on the scalar type.
56 template<typename S>
57 void expect_eps_values(const char* type_name) {
58  static_assert(std::is_floating_point<S>::value,
59  "Only use this helper for float and double types");
60  S expected_eps = std::numeric_limits<S>::epsilon();
61  // This is *explicitly* testing for perfect bit equivalency. The two values
62  // should be absolutely the same.
63  EXPECT_EQ(constants<S>::eps(), expected_eps) << "Failed for " << type_name;
64  EXPECT_EQ(std::pow(expected_eps, S(0.5)), constants<S>::eps_12())
65  << "Failed for " << type_name;
66  EXPECT_EQ(std::pow(expected_eps, S(0.75)), constants<S>::eps_34())
67  << "Failed for " << type_name;
68  EXPECT_EQ(std::pow(expected_eps, S(0.875)), constants<S>::eps_78())
69  << "Failed for " << type_name;
70 }
71 
72 // Test that the values returned are truly a function of the precision of the
73 // underlying type.
74 GTEST_TEST(FCL_CONSTANTS_EPS, precision_dependent) {
75  expect_eps_values<double>("double");
76  expect_eps_values<float>("float");
77  // Double check that the float value and double values are *not* equal.
78  EXPECT_NE(constantsd::eps(), constantsf::eps());
79  EXPECT_NE(constantsd::eps_12(), constantsf::eps_12());
80  EXPECT_NE(constantsd::eps_34(), constantsf::eps_34());
81  EXPECT_NE(constantsd::eps_78(), constantsf::eps_78());
82 }
83 
84 template <typename S> void expect_autodiff_constants(const char *type_name) {
85  EXPECT_TRUE((std::is_same<decltype(constants<AutoDiff2<S>>::pi()),
86  AutoDiff2<S>>::value))
87  << "Failed for " << type_name;
88  EXPECT_TRUE((std::is_same<decltype(constants<AutoDiff2<S>>::phi()),
89  AutoDiff2<S>>::value))
90  << "Failed for " << type_name;
92  (std::is_same<decltype(constants<AutoDiff2<S>>::eps()), S>::value))
93  << "Failed for " << type_name;
95  (std::is_same<decltype(constants<AutoDiff2<S>>::eps_78()), S>::value))
96  << "Failed for " << type_name;
98  (std::is_same<decltype(constants<AutoDiff2<S>>::eps_34()), S>::value))
99  << "Failed for " << type_name;
100  EXPECT_TRUE(
101  (std::is_same<decltype(constants<AutoDiff2<S>>::eps_12()), S>::value))
102  << "Failed for " << type_name;
103 }
104 
105 // Test the types returned by constants. pi and phi should return autodiff, but
106 // the tolerances should return real types.
107 GTEST_TEST(FCL_CONSTANTS_EPS, autodiff_compatibility) {
108  expect_autodiff_constants<double>("double");
109  expect_autodiff_constants<float>("float");
110 }
111 
112 } // namespace
113 } // namespace fcl
114 
115 //==============================================================================
116 int main(int argc, char* argv[])
117 {
118  ::testing::InitGoogleTest(&argc, argv);
119  return RUN_ALL_TESTS();
120 }
fcl::constants::eps_34
static Real eps_34()
Returns ε^(3/4) for the precision of the underlying scalar type.
Definition: constants.h:170
fcl::constants::eps_78
static Real eps_78()
Returns ε^(7/8) for the precision of the underlying scalar type.
Definition: constants.h:164
epsilon
S epsilon()
Definition: test_fcl_simple.cpp:56
fcl::constants::eps
static constexpr Real eps()
Returns ε for the precision of the underlying scalar type.
Definition: constants.h:151
EXPECT_TRUE
#define EXPECT_TRUE(args)
fcl::Vector2
Eigen::Matrix< S, 2, 1 > Vector2
Definition: types.h:67
GTEST_TEST
GTEST_TEST(DynamicAABBTreeCollisionManager, update)
Definition: test_broadphase_dynamic_AABB_tree.cpp:61
constants.h
fcl::constants::eps_12
static Real eps_12()
Returns ε^(1/2) for the precision of the underlying scalar type.
Definition: constants.h:176
main
int main(int argc, char *argv[])
Definition: test_fcl_constant_eps.cpp:116
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