AP_Math: fixed vel correction test build

This commit is contained in:
Andrew Tridgell 2021-07-01 09:26:07 +10:00
parent c059f8c044
commit 31a6663797

View File

@ -628,7 +628,7 @@ TEST(MathTest, VELCORRECTION)
static constexpr Matrix3F rot(0.0f, -1.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f);
static constexpr Vector3F rate{-1.0f, -1.0f, -1.0f};
EXPECT_TRUE(Vector3F(1.0f, 1.0f, 0.0f) == get_vel_correction_for_sensor_offset(pos, rot, rate));
EXPECT_TRUE(Vector3F() == get_vel_correction_for_sensor_offset(Vector3f(), rot, rate));
EXPECT_TRUE(Vector3F() == get_vel_correction_for_sensor_offset(Vector3F(), rot, rate));
}
TEST(MathTest, LOWPASSALPHA)