mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_Math: pragma away the float-equal test for the maths tests
There are legitimate reasons for doing direct equivalence in these files
This commit is contained in:
parent
3e9294a2ae
commit
43f3d611b2
@ -1,3 +1,9 @@
|
||||
|
||||
// given we are in the Math library, you're epected to know what
|
||||
// you're doing when directly comparing floats:
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wfloat-equal"
|
||||
|
||||
#include <AP_gtest.h>
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
@ -290,3 +296,5 @@ TEST(MathWrapTest, Angle2PI)
|
||||
}
|
||||
|
||||
AP_GTEST_MAIN()
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
@ -17,6 +17,11 @@
|
||||
|
||||
#include "math_test.h"
|
||||
|
||||
// given we are in the Math library, you're epected to know what
|
||||
// you're doing when directly comparing floats:
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wfloat-equal"
|
||||
|
||||
#define AP_EXPECT_IDENTITY_MATRIX(m_) {\
|
||||
EXPECT_NEAR(1.0f, m_.a.x, 1.0e-6); \
|
||||
EXPECT_NEAR(0.0f, m_.a.y, 1.0e-6); \
|
||||
@ -105,3 +110,5 @@ INSTANTIATE_TEST_CASE_P(NonInvertibleMatrices,
|
||||
::testing::ValuesIn(non_invertible));
|
||||
|
||||
AP_GTEST_MAIN()
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
Loading…
Reference in New Issue
Block a user