mirror of https://github.com/ArduPilot/ardupilot
AP_Math: add another test for wrap_360_cd
This commit is contained in:
parent
e0f63ca7f1
commit
dc14d7bce4
|
@ -261,6 +261,7 @@ TEST(MathWrapTest, Angle360)
|
|||
EXPECT_EQ(18000.f, wrap_360_cd(18000.f));
|
||||
EXPECT_EQ(27000.f, wrap_360_cd(27000.f));
|
||||
EXPECT_EQ(0.f, wrap_360_cd(36000.f));
|
||||
EXPECT_EQ(5.f, wrap_360_cd(36005.f));
|
||||
EXPECT_EQ(0.f, wrap_360_cd(72000.f));
|
||||
EXPECT_EQ(0.f, wrap_360_cd(360000.f));
|
||||
EXPECT_EQ(0.f, wrap_360_cd(720000.f));
|
||||
|
@ -271,6 +272,7 @@ TEST(MathWrapTest, Angle360)
|
|||
EXPECT_EQ(18000.f, wrap_360_cd(-18000.f));
|
||||
EXPECT_EQ(9000.f, wrap_360_cd(-27000.f));
|
||||
EXPECT_EQ(0.f, wrap_360_cd(-36000.f));
|
||||
EXPECT_EQ(35995.0f,wrap_360_cd(-36005.f));
|
||||
EXPECT_EQ(0.f, wrap_360_cd(-72000.f));
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue