mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_Math: tests: make both arguments double
libraries/AP_Math/tests/test_math.cpp.3.o: In function `MathTest_IsEqual_Test::TestBody()': test_math.cpp:(.text._ZN21MathTest_IsEqual_Test8TestBodyEv+0x1a0): undefined reference to `std::enable_if<std::is_floating_point<std::common_type<float, double>::type>::value, bool>::type is_equal<float, double>(float, double)' collect2: error: ld returned 1 exit status
This commit is contained in:
parent
00ef0cec2e
commit
2b9478f430
@ -84,7 +84,7 @@ TEST(MathTest, IsEqual)
|
||||
EXPECT_TRUE(is_equal(1.f, (float)(1.f - DBL_EPSILON)));
|
||||
|
||||
// false because the common type is double
|
||||
EXPECT_FALSE(is_equal(1., 1. + 2 * std::numeric_limits<double>::epsilon()));
|
||||
EXPECT_FALSE(is_equal(double(1.), 1 + 2 * std::numeric_limits<double>::epsilon()));
|
||||
|
||||
// true because the common type is float
|
||||
EXPECT_TRUE(is_equal(1.f, (float)(1. + std::numeric_limits<double>::epsilon())));
|
||||
|
Loading…
Reference in New Issue
Block a user