AP_Math: mark test_math_double.cpp as double precision source

fixed test_math_double
the wrap check needs to be wrap_PI() as otherwise rounding of 2*PI if
just over 6.28 will give a large error
ensure double tests are double
test_vector2
This commit is contained in:
Andrew Tridgell 2023-06-22 08:38:35 +10:00 committed by Peter Hall
parent d94e36fccc
commit e97f5d8012
4 changed files with 4 additions and 5 deletions

View File

@ -3,7 +3,6 @@
// you're doing when directly comparing floats:
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
#define ALLOW_DOUBLE_MATH_FUNCTIONS
#include <AP_gtest.h>
#include <AP_Math/AP_Math.h>
@ -187,8 +186,8 @@ TEST(MathWrapTest, Angle2PIDouble)
const double accuracy = 1.0e-5;
EXPECT_NEAR(M_PI, wrap_2PI((double)M_PI), accuracy);
EXPECT_NEAR(0.0, wrap_2PI((double)M_2PI), accuracy);
EXPECT_NEAR(0.0, wrap_2PI((double)M_PI * 10.0), accuracy);
EXPECT_NEAR(0.0, wrap_PI((double)M_2PI), accuracy);
EXPECT_NEAR(0.0, wrap_PI((double)M_PI * 10.0), accuracy);
EXPECT_NEAR(0.0, wrap_2PI(0.0), accuracy);
EXPECT_NEAR(M_PI, wrap_2PI((double)-M_PI), accuracy);
EXPECT_NEAR(0, wrap_2PI((double)-M_2PI), accuracy);

View File

@ -111,7 +111,7 @@ TEST(Vector2Test, angle)
{
EXPECT_FLOAT_EQ(M_PI/2, Vector2f(0, 1).angle());
EXPECT_FLOAT_EQ(M_PI/4, Vector2f(1, 1).angle());
EXPECT_FLOAT_EQ(0.0f, Vector2d(1, 0).angle());
EXPECT_TRUE(is_zero(Vector2d(1, 0).angle()));
EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-1, -1).angle());
EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-5, -5).angle());

View File

@ -1,5 +1,4 @@
#include <AP_gtest.h>
#define ALLOW_DOUBLE_MATH_FUNCTIONS
#include <AP_Math/AP_Math.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();

View File

@ -4,4 +4,5 @@
def build(bld):
bld.ap_find_tests(
use='ap',
DOUBLE_PRECISION_SOURCES = ['test_math_double.cpp', 'test_vector3.cpp']
)