mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
test_3d_lines:fix test result for test_3d_lines
This commit is contained in:
parent
4513546845
commit
abb0bf34d2
@ -26,7 +26,7 @@ TEST(Lines3dTests, ClosestDistBetweenLinePoint)
|
|||||||
|
|
||||||
// check protection agains null length
|
// check protection agains null length
|
||||||
const Vector3f intersection_null = Vector3f::point_on_line_closest_to_other_point(Vector3f{1.0f, 1.0f, 1.0f}, Vector3f{1.0f, 1.0f, 1.0f}, Vector3f{0.0f, 5.0f, 5.0f});
|
const Vector3f intersection_null = Vector3f::point_on_line_closest_to_other_point(Vector3f{1.0f, 1.0f, 1.0f}, Vector3f{1.0f, 1.0f, 1.0f}, Vector3f{0.0f, 5.0f, 5.0f});
|
||||||
EXPECT_VECTOR3F_EQ((Vector3f{0.0f, 0.0f, 0.0f}), intersection_null);
|
EXPECT_VECTOR3F_EQ((Vector3f{1.0f, 1.0f, 1.0f}), intersection_null);
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(Lines3dTests, SegmentToSegmentCloestPoint)
|
TEST(Lines3dTests, SegmentToSegmentCloestPoint)
|
||||||
|
Loading…
Reference in New Issue
Block a user