Skip to content

Commit

Permalink
Suggestions to #219
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
Signed-off-by: Arjo Chakravarty <[email protected]>
  • Loading branch information
chapulina authored and arjo129 committed Sep 20, 2021
1 parent c835aee commit b1a172f
Show file tree
Hide file tree
Showing 8 changed files with 115 additions and 17 deletions.
6 changes: 3 additions & 3 deletions include/ignition/math/Plane.hh
Original file line number Diff line number Diff line change
Expand Up @@ -122,9 +122,9 @@ namespace ignition
return this->normal.Dot(_point) - this->d;
}

/// \brief Get the intersection of a line with the plane
/// \brief Get the intersection of an infinite line with the plane,
/// given the line's gradient and a point in parametrized space.
/// \param[in] _point A point that lies on a line.
/// \param[in] _point A point that lies on the line.
/// \param[in] _gradient The gradient of the line.
/// \param[in] _tolerance The tolerance for determining a line is
/// parallel to the plane. Optional, default=10^-16
Expand All @@ -140,7 +140,7 @@ namespace ignition
return std::nullopt;
}
auto constant = this->Offset() - this->Normal().Dot(_point);
auto param = constant/this->Normal().Dot(_gradient);
auto param = constant / this->Normal().Dot(_gradient);
auto intersection = _point + _gradient*param;
return intersection;
}
Expand Down
5 changes: 3 additions & 2 deletions include/ignition/math/Sphere.hh
Original file line number Diff line number Diff line change
Expand Up @@ -94,12 +94,13 @@ namespace ignition

/// \brief Get the volume of sphere below a given plane in m^3.
/// It is assumed that the center of the sphere is on the origin
/// The plane's orientation is not considered.
/// \param[in] _plane The plane which slices this sphere.
/// \return Volume below the sphere in m^3.
public: Precision VolumeBelow(const Planed &_plane) const;

/// \brief Center of volume below the plane. This is useful when
/// calculating where the buoyancy should be applied.
/// \brief Center of volume below the plane. This is useful for example
/// when calculating where buoyancy should be applied.
/// \param[in] _plane The plane which slices the sphere.
/// \return The center of volume if there is anything under the plane,
/// otherwise return a std::nullopt.
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/math/Vector3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -272,7 +272,7 @@ namespace ignition
return this->Dot(_v) / this->Length();
}

/// \brief Get distance to a line
/// \brief Get distance to an infinite line defined by 2 points.
/// \param[in] _pt1 first point on the line
/// \param[in] _pt2 second point on the line
/// \return the minimum distance from this point to the line
Expand Down
14 changes: 10 additions & 4 deletions include/ignition/math/detail/Sphere.hh
Original file line number Diff line number Diff line change
Expand Up @@ -103,18 +103,24 @@ T Sphere<T>::VolumeBelow(const Planed &_plane) const
// get nearest point to center on plane
auto dist = _plane.Distance(Vector3d(0, 0, 0));

if(dist < -r)
if (dist < -r)
{
// sphere is completely below plane
return Volume();
}
else if(dist > r)
else if (dist > r)
{
// sphere is completely above plane
return 0;
return 0.0;
}

auto h = r + dist;
// Vertical plane
if (_plane.Normal().Z() < 1e-6)
{
return 0.0;
}

auto h = r - dist;
return IGN_PI * h * h * (3 * r - h) / 3;
}

Expand Down
6 changes: 3 additions & 3 deletions src/Line3_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -278,17 +278,17 @@ TEST(Line3Test, DistanceToPoint)
// Point projected onto the line
{
math::Vector3d point(1, -1, 0);
EXPECT_NEAR(line.Distance(point), point.Length(), 1e-3);
EXPECT_DOUBLE_EQ(line.Distance(point), point.Length());
}

// Points projected beyond the line's ends
{
math::Vector3d point(2, 2, 3);
EXPECT_NEAR(line.Distance(point), point.Distance(pointA), 1e-3);
EXPECT_DOUBLE_EQ(line.Distance(point), point.Distance(pointA));
}
{
math::Vector3d point(-5, -3, -8);
EXPECT_NEAR(line.Distance(point), point.Distance(pointB), 1e-3);
EXPECT_DOUBLE_EQ(line.Distance(point), point.Distance(pointB));
}
}

Expand Down
24 changes: 21 additions & 3 deletions src/Plane_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,25 @@ TEST(PlaneTest, SideAxisAlignedBox)
TEST(PlaneTest, Intersection)
{
Planed plane(Vector3d(0.5, 0, 1), 1);
auto intersect = plane.Intersection(Vector3d(0, 0, 0), Vector3d(1, 0, 1));
EXPECT_TRUE(intersect.has_value());
EXPECT_NEAR(intersect->Dot(plane.Normal()), plane.Offset(), 1e-6);
{
auto intersect = plane.Intersect(Vector3d(0, 0, 0), Vector3d(1, 0, 1));
EXPECT_TRUE(intersect.has_value());
EXPECT_NEAR(intersect->Dot(plane.Normal()), plane.Offset(), 1e-6);
}

plane.Set(Vector3d(1, 0, 0), 2);
{
auto intersect = plane.Intersect(Vector3d(0, 0, 0), Vector3d(1, 0, 0));
EXPECT_TRUE(intersect.has_value());
EXPECT_EQ(intersect.value(), Vector3d(2, 0, 0));
}
{
auto intersect = plane.Intersect(Vector3d(1, 1, 0), Vector3d(-1, -1, 0));
EXPECT_TRUE(intersect.has_value());
EXPECT_EQ(intersect.value(), Vector3d(2, 2, 0));
}
{
auto intersect = plane.Intersect(Vector3d(0, 0, 0), Vector3d(0, 1, 0));
EXPECT_FALSE(intersect.has_value());
}
}
45 changes: 44 additions & 1 deletion src/Sphere_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -138,18 +138,61 @@ TEST(SphereTest, VolumeBelow)
double r = 2;
math::Sphered sphere(r);

// Fully below
{
math::Planed _plane(math::Vector3d{0, 0, 1}, math::Vector2d(4, 4), 2*r);
EXPECT_NEAR(sphere.Volume(), sphere.VolumeBelow(_plane), 1e-3);
}
{
math::Planed _plane(math::Vector3d{0, 0, -1}, math::Vector2d(4, 4), 2*r);
EXPECT_NEAR(sphere.Volume(), sphere.VolumeBelow(_plane), 1e-3);
}

// Fully above
{
math::Planed _plane(math::Vector3d{0, 0, 1}, math::Vector2d(4, 4), -2*r);
EXPECT_NEAR(sphere.VolumeBelow(_plane), 0, 1e-3);
}

// Hemisphere
{
math::Planed _plane(math::Vector3d{0, 0, 1}, 0);
EXPECT_NEAR(sphere.Volume()/2, sphere.VolumeBelow(_plane), 1e-3);
EXPECT_NEAR(sphere.Volume() / 2, sphere.VolumeBelow(_plane), 1e-3);
}

// Vertical plane
{
math::Planed _plane(math::Vector3d{1, 0, 0}, 0);
EXPECT_NEAR(0.0, sphere.VolumeBelow(_plane), 1e-3);
}

// Expectations from https://planetcalc.com/283/
{
math::Planed _plane(math::Vector3d{0, 0, 1}, 0.5);
EXPECT_NEAR(22.90745, sphere.VolumeBelow(_plane), 1e-3);
}

{
math::Planed _plane(math::Vector3d{0, 0, 1}, -0.5);
EXPECT_NEAR(10.60288, sphere.VolumeBelow(_plane), 1e-3);
}
}

//////////////////////////////////////////////////
TEST(SphereTest, CenterOfVolumeBelow)
{
double r = 2;
math::Sphered sphere(r);

{
math::Planed _plane(math::Vector3d{0, 0, 1}, math::Vector2d(4, 4), 2*r);
EXPECT_EQ(Vector3d(0, 0, 0), sphere.CenterOfVolumeBelow(_plane));
}

{
math::Planed _plane(math::Vector3d{0, 0, 1}, math::Vector2d(4, 4), -2*r);
EXPECT_FALSE(sphere.CenterOfVolumeBelow(_plane));
}

// TODO: test more cases
}
30 changes: 30 additions & 0 deletions src/Vector3_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -516,3 +516,33 @@ TEST(Vector3dTest, NaN)
EXPECT_EQ(math::Vector3f::Zero, nanVecF);
EXPECT_TRUE(nanVecF.IsFinite());
}

/////////////////////////////////////////////////
TEST(Vector3dTest, DistToLine)
{
// Line on horizontal plane
math::Vector3d pointA{0, -1, 0};
math::Vector3d pointB{0, 1, 0};

// Point on the line
{
math::Vector3d point(0, 0.5, 0);
EXPECT_DOUBLE_EQ(point.DistToLine(pointA, pointB), 0.0);
}

// Points projected onto the line
{
math::Vector3d point(5, 0, 0);
EXPECT_DOUBLE_EQ(point.DistToLine(pointA, pointB), 5);
}
{
math::Vector3d point(-1, -1, 0);
EXPECT_DOUBLE_EQ(point.DistToLine(pointA, pointB), 1);
}

// Point projected beyond the segment's ends
{
math::Vector3d point(0, 2, 0);
EXPECT_DOUBLE_EQ(point.DistToLine(pointA, pointB), 0);
}
}

0 comments on commit b1a172f

Please sign in to comment.