Tweeker Commit (Have Fun Reviewing This)
This commit is contained in:
@@ -30,6 +30,8 @@ namespace J3ML::Geometry
|
||||
|
||||
AABB(const Vector3& min, const Vector3& max);
|
||||
|
||||
Vector3 HalfDiagonal() const { return HalfSize(); }
|
||||
|
||||
static int NumFaces() { return 6; }
|
||||
|
||||
static int NumEdges() { return 12; }
|
||||
@@ -90,6 +92,8 @@ namespace J3ML::Geometry
|
||||
|
||||
Plane FacePlane(int faceIndex) const;
|
||||
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
|
||||
static AABB MinimalEnclosingAABB(const Vector3 *pointArray, int numPoints);
|
||||
float GetVolume() const;
|
||||
float GetSurfaceArea() const;
|
||||
|
@@ -7,6 +7,15 @@
|
||||
|
||||
namespace J3ML::Geometry
|
||||
{
|
||||
// TODO: Move to separate math lib, find duplicates!
|
||||
template <typename T>
|
||||
void Swap(T &a, T &b)
|
||||
{
|
||||
T temp = std::move(a);
|
||||
a = std::move(b);
|
||||
b = std::move(temp);
|
||||
}
|
||||
|
||||
using namespace LinearAlgebra;
|
||||
class Capsule : public Shape
|
||||
{
|
||||
@@ -27,5 +36,31 @@ namespace J3ML::Geometry
|
||||
Vector3 Centroid() const;
|
||||
Vector3 ExtremePoint(const Vector3& direction);
|
||||
AABB MinimalEnclosingAABB() const;
|
||||
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
|
||||
bool Intersects(const Plane &plane) const;
|
||||
|
||||
bool Intersects(const Ray &ray) const;
|
||||
|
||||
bool Intersects(const Line &line) const;
|
||||
|
||||
bool Intersects(const LineSegment &lineSegment) const;
|
||||
|
||||
bool Intersects(const AABB &aabb) const;
|
||||
|
||||
bool Intersects(const OBB &obb) const;
|
||||
|
||||
bool Intersects(const Sphere &sphere) const;
|
||||
|
||||
bool Intersects(const Capsule &capsule) const;
|
||||
|
||||
bool Intersects(const Triangle &triangle) const;
|
||||
|
||||
bool Intersects(const Polygon &polygon) const;
|
||||
|
||||
bool Intersects(const Frustum &frustum) const;
|
||||
|
||||
bool Intersects(const Polyhedron &polyhedron) const;
|
||||
};
|
||||
}
|
@@ -10,6 +10,7 @@ namespace J3ML::Geometry
|
||||
class Capsule;
|
||||
class Frustum;
|
||||
class LineSegment;
|
||||
class Line;
|
||||
class OBB;
|
||||
class Plane;
|
||||
class Polygon;
|
||||
|
@@ -207,5 +207,9 @@ namespace J3ML::Geometry
|
||||
bool Intersects(const Capsule& obb) const;
|
||||
bool Intersects(const Frustum& plane) const;
|
||||
bool Intersects(const Polyhedron& triangle) const;
|
||||
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
|
||||
void GetCornerPoints(Vector3 *outPointArray) const;
|
||||
};
|
||||
}
|
@@ -1,10 +1,24 @@
|
||||
#pragma once
|
||||
|
||||
|
||||
#include "LineSegment.h"
|
||||
|
||||
namespace J3ML::Geometry
|
||||
{
|
||||
class Line
|
||||
{
|
||||
public:
|
||||
Vector3 Position; /// Specifies the origin of this line.
|
||||
Vector3 Direction; /// The normalized direction vector of this ray.
|
||||
public:
|
||||
static void
|
||||
ClosestPointLineLine(const Vector3 &v0, const Vector3 &v10, const Vector3 &v2, const Vector3 &v32, float &d,
|
||||
float &d2);
|
||||
|
||||
Vector3 ClosestPoint(const J3ML::Geometry::LineSegment &other, float &d, float &d2) const;
|
||||
|
||||
Vector3 GetPoint(float d) const;
|
||||
|
||||
Vector3 ClosestPoint(const Vector3 &targetPoint, float &d) const;
|
||||
};
|
||||
}
|
@@ -1,9 +1,26 @@
|
||||
#pragma once
|
||||
|
||||
#include <J3ML/LinearAlgebra/Vector3.h>
|
||||
#include "Plane.h"
|
||||
#include <J3ML/Geometry/Common.h>
|
||||
|
||||
namespace J3ML::Geometry
|
||||
{
|
||||
|
||||
/// Clamps the given input value to the range [min, max].
|
||||
/** @see Clamp01(), Min(), Max(). */
|
||||
template<typename T>
|
||||
T Clamp(const T &val, const T &floor, const T &ceil)
|
||||
{
|
||||
assert(floor <= ceil);
|
||||
return val <= ceil ? (val >= floor ? val : floor) : ceil;
|
||||
}
|
||||
|
||||
/// Clamps the given input value to the range [0, 1].
|
||||
/** @see Clamp(), Min(), Max(). */
|
||||
template<typename T>
|
||||
T Clamp01(const T &val) { return Clamp(val, T(0), T(1)); }
|
||||
|
||||
using LinearAlgebra::Vector3;
|
||||
class LineSegment
|
||||
{
|
||||
@@ -13,5 +30,35 @@ namespace J3ML::Geometry
|
||||
Vector3 A;
|
||||
Vector3 B;
|
||||
bool Contains(const Vector3&) const;
|
||||
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
Vector3 GetPoint(float d) const;
|
||||
Vector3 ClosestPoint(const Vector3 &point, float &d) const;
|
||||
Vector3 ClosestPoint(const Ray &other, float &d, float &d2) const;
|
||||
float Distance(const Vector3 &point) const;
|
||||
float DistanceSq(const Vector3& point) const;
|
||||
float Distance(const Vector3 &point, float &d) const;
|
||||
float Distance(const Ray &other) const;
|
||||
float Distance(const Ray &other, float &d) const;
|
||||
float Distance(const Ray &other, float &d, float &d2) const;
|
||||
float Distance(const Line &other) const;
|
||||
float Distance(const Line &other, float &d) const;
|
||||
float Distance(const Line &other, float &d, float &d2) const;
|
||||
float Distance(const LineSegment &other) const;
|
||||
float Distance(const LineSegment &other, float &d) const;
|
||||
float Distance(const LineSegment &other, float &d, float &d2) const;
|
||||
float Distance(const Plane& other) const;
|
||||
|
||||
Vector3 Dir() const;
|
||||
|
||||
float Length() const;
|
||||
|
||||
float LengthSq() const;
|
||||
|
||||
float DistanceSq(const LineSegment &other) const;
|
||||
|
||||
Vector3 ClosestPoint(const LineSegment &other, float &d, float &d2) const;
|
||||
|
||||
Vector3 ClosestPoint(const Line &other, float &d, float &d2) const;
|
||||
};
|
||||
}
|
@@ -94,5 +94,7 @@ namespace J3ML::Geometry {
|
||||
void SetFrom(const AABB &aabb, const Matrix4x4 &transform);
|
||||
|
||||
void SetFrom(const AABB &aabb, const Quaternion &transform);
|
||||
|
||||
bool Intersects(const Plane& plane) const;
|
||||
};
|
||||
}
|
@@ -11,22 +11,74 @@ namespace J3ML::Geometry
|
||||
class Plane : public Shape
|
||||
{
|
||||
public:
|
||||
Plane() : Shape() {}
|
||||
Plane(const Vector3& v1, const Vector3 &v2, const Vector3& v3)
|
||||
{
|
||||
Set(v1, v2, v3);
|
||||
}
|
||||
Plane(const Vector3& pos, const Vector3& norm)
|
||||
: Shape(), Position(pos), Normal(norm) {}
|
||||
Vector3 Position;
|
||||
Vector3 Normal;
|
||||
float distance = 0.f;
|
||||
public:
|
||||
Plane() : Shape() {}
|
||||
Plane(const Vector3& v1, const Vector3 &v2, const Vector3& v3);
|
||||
Plane(const Vector3& pos, const Vector3& norm);
|
||||
Plane(const Line &line, const Vector3 &normal);
|
||||
|
||||
void Set(const Vector3& v1, const Vector3& v2, const Vector3& v3)
|
||||
{
|
||||
void Set(const Vector3& v1, const Vector3& v2, const Vector3& v3);
|
||||
|
||||
}
|
||||
void Set(const Vector3 &point, const Vector3 &normal_);
|
||||
|
||||
bool Intersects(J3ML::Geometry::Ray ray, float *pDouble);
|
||||
bool Intersects(J3ML::Geometry::Ray ray, float *dist) const;
|
||||
|
||||
/// Tests if the given point lies on the positive side of this plane.
|
||||
/** A plane divides the space in three sets: the negative halfspace, the plane itself, and the positive halfspace.
|
||||
The normal vector of the plane points towards the positive halfspace.
|
||||
@return This function returns true if the given point lies either on this plane itself, or in the positive
|
||||
halfspace of this plane.
|
||||
@see IsInPositiveDirection, AreOnSameSide(), Distance(), SignedDistance(). */
|
||||
bool IsOnPositiveSide(const Vector3 &point) const;
|
||||
|
||||
float SignedDistance(const Vector3 &point) const;
|
||||
float SignedDistance(const AABB &aabb) const;
|
||||
float SignedDistance(const OBB &obb) const;
|
||||
float SignedDistance(const Capsule &capsule) const;
|
||||
//float Plane::SignedDistance(const Circle &circle) const { return Plane_SignedDistance(*this, circle); }
|
||||
float SignedDistance(const Frustum &frustum) const;
|
||||
//float SignedDistance(const Line &line) const { return Plane_SignedDistance(*this, line); }
|
||||
float SignedDistance(const LineSegment &lineSegment) const;
|
||||
float SignedDistance(const Ray &ray) const;
|
||||
//float Plane::SignedDistance(const Plane &plane) const { return Plane_SignedDistance(*this, plane); }
|
||||
float SignedDistance(const Polygon &polygon) const;
|
||||
float SignedDistance(const Polyhedron &polyhedron) const;
|
||||
float SignedDistance(const Sphere &sphere) const;
|
||||
float SignedDistance(const Triangle &triangle) const;
|
||||
|
||||
static bool
|
||||
IntersectLinePlane(const Vector3 &planeNormal, float planeD, const Vector3 &linePos, const Vector3 &lineDir,
|
||||
float &t);
|
||||
|
||||
float Distance(const Vector3 &) const;
|
||||
|
||||
float Distance(const LineSegment &lineSegment) const;
|
||||
|
||||
float Distance(const Sphere &sphere) const;
|
||||
|
||||
float Distance(const Capsule &capsule) const;
|
||||
|
||||
bool Intersects(const Line &line, float *dist) const;
|
||||
|
||||
bool Intersects(const LineSegment &lineSegment, float *dist) const;
|
||||
|
||||
bool Intersects(const Sphere &sphere) const;
|
||||
|
||||
bool Intersects(const Capsule &capsule) const;
|
||||
|
||||
bool Intersects(const AABB &aabb) const;
|
||||
|
||||
bool Intersects(const OBB &obb) const;
|
||||
|
||||
bool Intersects(const Triangle &triangle) const;
|
||||
|
||||
bool Intersects(const Frustum &frustum) const;
|
||||
|
||||
bool Intersects(const Polyhedron &polyhedron) const;
|
||||
|
||||
LineSegment Project(const LineSegment &segment);
|
||||
};
|
||||
}
|
@@ -12,17 +12,52 @@ namespace J3ML::Geometry {
|
||||
public:
|
||||
std::vector<Vector3> vertices;
|
||||
AABB MinimalEnclosingAABB() const;
|
||||
int NumVertices() const
|
||||
{
|
||||
return (int)vertices.size();
|
||||
}
|
||||
Vector3 Vertex(int vertexIndex) const
|
||||
{
|
||||
assert(vertexIndex >= 0);
|
||||
assert(vertexIndex < (int) vertices.size());
|
||||
return vertices[vertexIndex];
|
||||
}
|
||||
int NumVertices() const;
|
||||
Vector3 Vertex(int vertexIndex) const;
|
||||
Vector3 ExtremePoint(const Vector3 &direction, float &projectionDistance) const;
|
||||
|
||||
Vector3 ExtremePoint(const Vector3 &direction) const;
|
||||
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
|
||||
bool Intersects(const Capsule &capsule) const;
|
||||
bool Intersects(const Line &line) const;
|
||||
bool Intersects(const Ray &ray) const;
|
||||
bool Intersects(const LineSegment &lineSegment) const;
|
||||
bool Intersects(const Plane &plane) const;
|
||||
bool Intersects(const AABB &aabb) const;
|
||||
bool Intersects(const OBB &obb) const;
|
||||
bool Intersects(const Triangle &triangle, float polygonThickness = 1e-3f) const;
|
||||
bool Intersects(const Polygon &polygon, float polygonThickness = 1e-3f) const;
|
||||
bool Intersects(const Frustum &frustum) const;
|
||||
bool Intersects(const Polyhedron &polyhedron) const;
|
||||
bool Intersects(const Sphere &sphere) const;
|
||||
|
||||
protected:
|
||||
private:
|
||||
|
||||
std::vector<Triangle> Triangulate() const;
|
||||
/// Tests if this polygon is planar.
|
||||
/** A polygon is planar if all its vertices lie on the same plane.
|
||||
@note Almost all functions in this class require that the polygon is planar. While you can store vertices of
|
||||
non-planar polygons in this class, they are better avoided. Read the member function documentation carefully
|
||||
to avoid calling for non-planar polygons any functions which assume planarity.
|
||||
@see IsConvex(), IsSimple(), IsNull(), IsFinite(), IsDegenerate(). */
|
||||
bool IsPlanar(float epsilonSq = 1e-4f) const;
|
||||
|
||||
Vector2 MapTo2D(int i) const;
|
||||
|
||||
Vector2 MapTo2D(const Vector3 &point) const;
|
||||
|
||||
Vector3 BasisU() const;
|
||||
|
||||
Vector3 BasisV() const;
|
||||
|
||||
Plane PlaneCCW() const;
|
||||
|
||||
bool Contains(const Polygon &worldSpacePolygon, float polygonThickness) const;
|
||||
|
||||
bool Contains(const Vector3 &worldSpacePoint, float polygonThicknessSq) const;
|
||||
|
||||
bool Contains(const LineSegment &worldSpaceLineSegment, float polygonThickness) const;
|
||||
};
|
||||
}
|
@@ -40,7 +40,7 @@ namespace J3ML::Geometry
|
||||
|
||||
Vector3 Vertex(int vertexIndex) const;
|
||||
|
||||
bool Intersects(const LineSegment&) const;
|
||||
|
||||
|
||||
bool Contains(const Vector3&) const;
|
||||
bool Contains(const LineSegment&) const;
|
||||
@@ -55,6 +55,8 @@ namespace J3ML::Geometry
|
||||
bool ContainsConvex(const LineSegment&) const;
|
||||
bool ContainsConvex(const Triangle&) const;
|
||||
|
||||
bool Intersects(const Line&) const;
|
||||
bool Intersects(const LineSegment&) const;
|
||||
bool Intersects(const Ray&) const;
|
||||
bool Intersects(const Plane&) const;
|
||||
bool Intersects(const Polyhedron&) const;
|
||||
@@ -84,9 +86,28 @@ namespace J3ML::Geometry
|
||||
|
||||
Polygon FacePolygon(int faceIndex) const;
|
||||
|
||||
Vector3 FaceNormal(int faceIndex) const;
|
||||
|
||||
bool IsConvex() const;
|
||||
|
||||
Vector3 ApproximateConvexCentroid() const;
|
||||
|
||||
int ExtremeVertex(const Vector3 &direction) const;
|
||||
|
||||
Vector3 ExtremePoint(const Vector3 &direction) const;
|
||||
|
||||
/// Tests if the given face of this Polyhedron contains the given point.
|
||||
bool FaceContains(int faceIndex, const Vector3 &worldSpacePoint, float polygonThickness = 1e-3f) const;
|
||||
|
||||
/// A helper for Contains() and FaceContains() tests: Returns a positive value if the given point is contained in the given face,
|
||||
/// and a negative value if the given point is outside the face. The magnitude of the return value reports a pseudo-distance
|
||||
/// from the point to the nearest edge of the face polygon. This is used as a robustness/stability criterion to estimate how
|
||||
/// numerically believable the result is.
|
||||
float FaceContainmentDistance2D(int faceIndex, const Vector3 &worldSpacePoint, float polygonThickness) const;
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
protected:
|
||||
private:
|
||||
|
||||
|
||||
};
|
||||
}
|
@@ -56,5 +56,11 @@ namespace J3ML::Geometry
|
||||
// the surface intersection point,
|
||||
// and the surface normal at the point of intersection.
|
||||
RaycastResult Cast(std::vector<Shape> shapes, float maxDistance = 99999999);
|
||||
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
|
||||
Vector3 ClosestPoint(const LineSegment&, float &d, float &d2) const;
|
||||
|
||||
Vector3 ClosestPoint(const Vector3 &targetPoint, float &d) const;
|
||||
};
|
||||
}
|
@@ -60,12 +60,10 @@ namespace J3ML::Geometry
|
||||
{
|
||||
return Position.DistanceSquared(point) <= Radius*Radius + epsilon;
|
||||
}
|
||||
bool Contains(const LineSegment& lineseg) const
|
||||
{
|
||||
|
||||
}
|
||||
bool Contains(const LineSegment& lineseg) const;
|
||||
TriangleMesh GenerateUVSphere() const {}
|
||||
TriangleMesh GenerateIcososphere() const {}
|
||||
|
||||
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
||||
};
|
||||
}
|
@@ -13,9 +13,79 @@ namespace J3ML::Geometry
|
||||
Vector3 V2;
|
||||
|
||||
bool Intersects(const AABB& aabb) const;
|
||||
bool Intersects(const Capsule& capsule) const;
|
||||
AABB BoundingAABB() const;
|
||||
|
||||
bool Contains(const Vector3&) const;
|
||||
|
||||
void ProjectToAxis(const Vector3 &axis, float &dMin, float &dMax) const;
|
||||
|
||||
|
||||
static float IntersectLineTri(const Vector3 &linePos, const Vector3 &lineDir, const Vector3 &v0, const Vector3 &v1,
|
||||
const Vector3 &v2, float &u, float &v);
|
||||
|
||||
/// Computes the closest point on the edge of this triangle to the given object.
|
||||
/** @param outU [out] If specified, receives the barycentric U coordinate of the returned point (in the UV convention).
|
||||
This pointer may be null.
|
||||
@param outV [out] If specified, receives the barycentric V coordinate of the returned point (in the UV convention).
|
||||
This pointer may be null.
|
||||
@param outD [out] If specified, receives the distance along the line of the closest point on the line to the edge of this triangle.
|
||||
@return The closest point on the edge of this triangle to the given object.
|
||||
@todo Add ClosestPointToTriangleEdge(Point/Ray/Triangle/Plane/Polygon/Circle/Disk/AABB/OBB/Sphere/Capsule/Frustum/Polyhedron).
|
||||
@see Distance(), Contains(), Intersects(), ClosestPointToTriangleEdge(), Line::GetPoint. */
|
||||
Vector3 ClosestPointToTriangleEdge(const Line &line, float *outU, float *outV, float *outD) const;
|
||||
Vector3 ClosestPointToTriangleEdge(const LineSegment &lineSegment, float *outU, float *outV, float *outD) const;
|
||||
|
||||
Vector3 ClosestPoint(const LineSegment &lineSegment, Vector3 *otherPt = 0) const;
|
||||
/// Returns the point at the given barycentric coordinates.
|
||||
/** This function computes the vector space point at the given barycentric coordinates.
|
||||
@param uvw The barycentric UVW coordinate triplet. The condition u+v+w == 1 should hold for the input coordinate.
|
||||
If 0 <= u,v,w <= 1, the returned point lies inside this triangle.
|
||||
@return u*a + v*b + w*c. */
|
||||
Vector3 Point(const Vector3 &uvw) const;
|
||||
Vector3 Point(float u, float v, float w) const;
|
||||
/** These functions are an alternate form of Point(u,v,w) for the case when the barycentric coordinates are
|
||||
represented as a (u,v) pair and not as a (u,v,w) triplet. This function is provided for convenience
|
||||
and effectively just computes Point(1-u-v, u, v).
|
||||
@param uv The barycentric UV coordinates. If 0 <= u,v <= 1 and u+v <= 1, then the returned point lies inside
|
||||
this triangle.
|
||||
@return a + (b-a)*u + (c-a)*v.
|
||||
@see BarycentricUV(), BarycentricUVW(), BarycentricInsideTriangle(). */
|
||||
Vector3 Point(const Vector2 &uv) const;
|
||||
Vector3 Point(float u, float v) const;
|
||||
|
||||
/// Expresses the given point in barycentric (u,v,w) coordinates.
|
||||
/** @note There are two different conventions for representing barycentric coordinates. One uses
|
||||
a (u,v,w) triplet with the equation pt == u*a + v*b + w*c, and the other uses a (u,v) pair
|
||||
with the equation pt == a + u*(b-a) + v*(c-a). These two are equivalent. Use the mappings
|
||||
(u,v) -> (1-u-v, u, v) and (u,v,w)->(v,w) to convert between these two representations.
|
||||
@param point The point of the vector space to express in barycentric coordinates. This point should
|
||||
lie in the plane formed by this triangle.
|
||||
@return The factors (u,v,w) that satisfy the weighted sum equation point == u*a + v*b + w*c.
|
||||
@see BarycentricUV(), BarycentricInsideTriangle(), Point(), http://mathworld.wolfram.com/BarycentricCoordinates.html */
|
||||
Vector3 BarycentricUVW(const Vector3 &point) const;
|
||||
|
||||
/// Expresses the given point in barycentric (u,v) coordinates.
|
||||
/** @note There are two different conventions for representing barycentric coordinates. One uses
|
||||
a (u,v,w) triplet with the equation pt == u*a + v*b + w*c, and the other uses a (u,v) pair
|
||||
with the equation pt == a + u*(b-a) + v*(c-a). These two are equivalent. Use the mappings
|
||||
(u,v) -> (1-u-v, u, v) and (u,v,w)->(v,w) to convert between these two representations.
|
||||
@param point The point to express in barycentric coordinates. This point should lie in the plane
|
||||
formed by this triangle.
|
||||
@return The factors (u,v) that satisfy the weighted sum equation point == a + u*(b-a) + v*(c-a).
|
||||
@see BarycentricUVW(), BarycentricInsideTriangle(), Point(). */
|
||||
Vector2 BarycentricUV(const Vector3 &point) const;
|
||||
|
||||
|
||||
Vector3 ClosestPoint(const Vector3 &p) const;
|
||||
|
||||
Plane PlaneCCW() const;
|
||||
|
||||
Plane PlaneCW() const;
|
||||
|
||||
Vector3 Vertex(int i) const;
|
||||
|
||||
LineSegment Edge(int i) const;
|
||||
};
|
||||
|
||||
|
||||
|
Reference in New Issue
Block a user