Skip to content

Commit

Permalink
AP_Math: add a test for rand_float
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tridge committed Aug 27, 2024
1 parent 84bcea7 commit 3c0c2bf
Showing 1 changed file with 17 additions and 0 deletions.
17 changes: 17 additions & 0 deletions libraries/AP_Math/tests/test_math.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -654,6 +654,23 @@ TEST(MathTest, RANDOM16)
EXPECT_NE(random_value, get_random16());
}

TEST(MathTest, RAND_FLOAT)
{
// bodgy range checks
float lowest_value = 0;
float highest_value = 0;
for (auto i=0; i<1000; i++) {
const auto value = rand_float();
lowest_value = MIN(lowest_value, value);
highest_value = MAX(highest_value, value);
}
EXPECT_NEAR(-0.95, lowest_value, 0.05);
EXPECT_NEAR(0.95, highest_value, 0.05);
EXPECT_GE(lowest_value, -1.0);
EXPECT_LE(highest_value, 1.0);

}

TEST(MathTest, VELCORRECTION)
{
static constexpr Vector3F pos{1.0f, 1.0f, 0.0f};
Expand Down

0 comments on commit 3c0c2bf

Please sign in to comment.