mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: Update segment_to_segment_dis test
This commit is contained in:
parent
730cf0ad9b
commit
b9fbf1a661
@ -29,20 +29,18 @@ TEST(Lines3dTests, ClosestDistBetweenLinePoint)
|
||||
EXPECT_VECTOR3F_EQ((Vector3f{0.0f, 0.0f, 0.0f}), intersection_null);
|
||||
}
|
||||
|
||||
TEST(Lines3dTests, SegmentToSegmentDistance)
|
||||
TEST(Lines3dTests, SegmentToSegmentCloestPoint)
|
||||
{
|
||||
// random segments test
|
||||
Vector3f intersection;
|
||||
float dist = Vector3f::segment_to_segment_dist(Vector3f{-10.0f,0.0f,0.0f}, Vector3f{10.0f,0.0f,0.0f}, Vector3f{0.0f, -5.0f, 1.0}, Vector3f{0.0f, 5.0f, 1.0f}, intersection);
|
||||
EXPECT_FLOAT_EQ(dist, 1.0f);
|
||||
Vector3f::segment_to_segment_closest_point(Vector3f{-10.0f,0.0f,0.0f}, Vector3f{10.0f,0.0f,0.0f}, Vector3f{0.0f, -5.0f, 1.0}, Vector3f{0.0f, 5.0f, 1.0f}, intersection);
|
||||
EXPECT_VECTOR3F_EQ(intersection, (Vector3f{0.0f, 0.0f, 1.0f}));
|
||||
|
||||
// check for intersecting segments. Verify with the 2-d variant
|
||||
dist = Vector3f::segment_to_segment_dist(Vector3f{}, Vector3f{10.0f,10.0f,0.0f}, Vector3f{2.0f, -10.0f, 0.0}, Vector3f{3.0f, 10.0f, 0.0f}, intersection);
|
||||
Vector3f::segment_to_segment_closest_point(Vector3f{}, Vector3f{10.0f,10.0f,0.0f}, Vector3f{2.0f, -10.0f, 0.0}, Vector3f{3.0f, 10.0f, 0.0f}, intersection);
|
||||
Vector2f intersection_2d;
|
||||
const bool result = Vector2f::segment_intersection(Vector2f{}, Vector2f{10.0f,10.0}, Vector2f{2.0f, -10.0f}, Vector2f{3.0f, 10.0f}, intersection_2d);
|
||||
EXPECT_EQ(true, result);
|
||||
EXPECT_FLOAT_EQ(dist, 0.0f);
|
||||
EXPECT_VECTOR3F_EQ(intersection, (Vector3f(intersection_2d.x, intersection_2d.y, 0.0f)));
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user