mirror of https://github.com/ArduPilot/ardupilot
AP_Common: ensure that constants are float not double if not otherwise declared
use correct DOUBLE_PRECISION_SOURCES definition portably define qsort argument in tests fix test_location add test_location to double sources
This commit is contained in:
parent
744028e79e
commit
d94e36fccc
|
@ -22,6 +22,9 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/* assert that const vals are float, not double. so 100.0 means 100.0f */
|
||||
static_assert(sizeof(1e6) == sizeof(float), "Compilation needs to use single-precision constants");
|
||||
|
||||
/*
|
||||
Return true if value is between lower and upper bound inclusive.
|
||||
False otherwise.
|
||||
|
|
|
@ -63,7 +63,7 @@ TEST(Location, LatLngWrapping)
|
|||
int32_t expected_lat;
|
||||
int32_t expected_lng;
|
||||
} tests[] {
|
||||
{519634000, 1797560000, Vector2f{0, 100000}, 519634000, -1787860775}
|
||||
{519634000, 1797560000, Vector2f{0, 100000}, 519634000, -1787860777}
|
||||
};
|
||||
|
||||
for (auto &test : tests) {
|
||||
|
@ -98,7 +98,7 @@ TEST(Location, LocOffsetDouble)
|
|||
-353632620, 1491652373,
|
||||
Vector2d{4682795.4576701336, 5953662.7673837934},
|
||||
Vector2d{4682797.1904749088, 5953664.1586009059},
|
||||
Vector2d{1.7365739867091179,1.2050807},
|
||||
Vector2d{1.7365739,1.4261966},
|
||||
};
|
||||
|
||||
for (auto &test : tests) {
|
||||
|
@ -282,8 +282,10 @@ TEST(Location, Distance)
|
|||
EXPECT_VECTOR2F_EQ(Vector3f(0, 0, 0), test_home.get_distance_NED(test_home));
|
||||
EXPECT_VECTOR2F_EQ(Vector3f(-11.131885, 0, 0), test_home.get_distance_NED(test_home2));
|
||||
Location test_loc = test_home;
|
||||
test_loc.offset(-11.131885, 0);
|
||||
test_loc.offset(-11.131886, 0);
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_home2));
|
||||
test_loc = test_home;
|
||||
test_loc.offset(-11.131885, 0);
|
||||
test_loc.offset_bearing(0, 11.131885);
|
||||
EXPECT_TRUE(test_loc.same_latlon_as(test_home));
|
||||
|
||||
|
|
|
@ -10,6 +10,8 @@
|
|||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
|
||||
typedef int (*compare_fn_t)(const void*, const void*);
|
||||
|
||||
static int comp16(const uint16_t *v1, const uint16_t *v2) {
|
||||
return int32_t(*v1) - int32_t(*v2);
|
||||
}
|
||||
|
@ -32,7 +34,7 @@ TEST(Sorting, sort)
|
|||
a1[j] = a2[j] = unsigned(random()) % maxval;
|
||||
}
|
||||
insertion_sort_uint16(a1, n);
|
||||
qsort(a2, n, sizeof(uint16_t), (__compar_fn_t)comp16);
|
||||
qsort(a2, n, sizeof(uint16_t), (compare_fn_t)comp16);
|
||||
check_equal(a1, a2, n);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -4,9 +4,5 @@
|
|||
def build(bld):
|
||||
bld.ap_find_tests(
|
||||
use='ap',
|
||||
DOUBLE_PRECISION_SOURCES = ['test_location.cpp']
|
||||
)
|
||||
|
||||
# location test needs double precision
|
||||
def configure(cfg):
|
||||
cfg.env.DOUBLE_PRECISION_SOURCES['AP_Common'] = ['tests/test_location.cpp']
|
||||
|
||||
|
|
Loading…
Reference in New Issue