Fixed several recursive header issues, refactored Math lib, began implementing core mathematical functions as wrappers around stdmath, will implement SSE and lookup tables later.
All checks were successful
Run ReCI Build Test / Explore-Gitea-Actions (push) Successful in 1m13s
Build Docs With Doxygen / Explore-Gitea-Actions (push) Successful in 19s

This commit is contained in:
2024-07-05 16:13:13 -04:00
parent bc7adae8af
commit 9253cfc8c7
27 changed files with 1217 additions and 335 deletions

View File

@@ -1,15 +1,27 @@
#pragma once
#include <format>
#include <optional>
#include <J3ML/LinearAlgebra.h>
#include <J3ML/LinearAlgebra/Common.h>
#include <J3ML/Geometry/Common.h>
#include <J3ML/Geometry/Shape.h>
#include "J3ML/Algorithm/RNG.h"
#include "Polygon.h"
#include "Sphere.h"
#include <J3ML/Algorithm/RNG.h>
namespace J3ML::Geometry
{
// TODO: Move this somewhere else to do goofy experiments!
template <typename T, typename = std::enable_if_t<std::is_arithmetic_v<T>, T>>
float fdiv(T a, T b) {
return (float)a/(b);
}
using namespace J3ML::LinearAlgebra;
using J3ML::Algorithm::RNG;
@@ -47,12 +59,25 @@ namespace J3ML::Geometry
@note Since an AABB cannot generally represent an OBB, this conversion is not exact, but the returned AABB
specifies a larger volume.
@see class OBB. */
explicit AABB(const OBB &obb);
explicit AABB(const OBB &obb) {
SetFrom(obb);
}
/// Constructs this AABB to enclose the given Sphere.
/** @see class Sphere. */
explicit AABB(const Sphere &s);
explicit AABB(const Sphere &s) {
SetFrom(s);
}
/// Returns the diameter vector of this AABB.
/** @note For AABB, Diagonal() and Size() are the same concept. These functions are provided for symmetry with the OBB class.
@see Size(), HalfDiagonal() */
Vector3 Diagonal() const { return Size(); }
/// Returns Diagonal()/2.
/// @see Diagonal(), HalfSize()
Vector3 HalfDiagonal() const { return HalfSize(); }
static AABB FromCenterAndSize(const Vector3 &center, const Vector3 &size);
@@ -184,6 +209,7 @@ namespace J3ML::Geometry
float SurfaceArea() const;
Vector3 GetClosestPoint(const Vector3& point) const;
void Translate(const Vector3& offset);
AABB Translated(const Vector3& offset) const;
void Scale(const Vector3& scale);
@@ -329,12 +355,27 @@ namespace J3ML::Geometry
void Enclose(const LineSegment &lineSegment);
void Enclose(const OBB &obb);
void Enclose(const Sphere &sphere);
void Enclose(const Triangle &triangle);
void Enclose(const Capsule &capsule);
void Enclose(const Frustum &frustum);
void Enclose(const Polygon &polygon);
void Enclose(const Polyhedron &polyhedron);
void Enclose(const Vector3 *pointArray, int numPoints);
void Enclose(const Frustum &frustum) {
//Enclose(frustum.MinimalEnclosingAABB());
}
void Enclose(const Polygon &polygon) {
//Enclose(polygon.MinimalEnclosingAABB());
}
void Enclose(const Polyhedron &polyhedron) {
//Enclose(polyhedron.MinimalEnclosingAABB());
}
void Enclose(const Vector3 *pointArray, int numPoints) {
assert(pointArray || numPoints == 0);
if (!pointArray)
return;
for (int i = 0; i < numPoints; ++i)
Enclose(pointArray[i]);
}
bool TestAxis(const Vector3& axis, const Vector3& v0, const Vector3& v1, const Vector3& v2) const;

View File

@@ -1,9 +1,9 @@
#pragma once
#include "LineSegment.h"
#include "Shape.h"
#include <J3ML/LinearAlgebra.h>
#include <J3ML/LinearAlgebra/Common.h>
#include <J3ML/Geometry/Common.h>
#include <J3ML/Geometry/Shape.h>
namespace J3ML::Geometry
{
@@ -63,12 +63,16 @@ namespace J3ML::Geometry
/// Tests if this Capsule is degenerate.
/** @return True if this Capsule does not span a strictly positive volume. */
bool IsDegenerate() const;
/// Computes the total height of this capsule, i.e. LineLength() + Diameter().
/** <img src="CapsuleFunctions.png" />
@see LineLength(). */
float Height() const;
/// Computes the distance of the two inner points of this capsule. @see Height.
float LineLength() const { return l.Length(); }
/// Computes the diameter of this capsule.
float Diameter() const;
float Diameter() const { return 2.f * r;}
/// Returns the bottom-most point of this Capsule.
/** <img src="CapsuleFunctions.png" />
@note The bottom-most point is only a naming convention, and does not correspond to the bottom-most point along any world axis. The returned
@@ -76,12 +80,13 @@ namespace J3ML::Geometry
@note The bottom-most point of the capsule is different than the point l.a. The returned point is the point at the very far
edge of this capsule, and does not lie on the internal line. See the attached diagram.
@see Top(), l. */
Vector3 Bottom() const;
Vector3 Bottom() const { return l.A - UpDirection() * r;}
/// Returns the center point of this Capsule.
/** <img src="doc/static/docs/CapsuleFunctions.png" />
@return The point (l.a + l.b) / 2. This point is the center of mass for this capsule.
@see l, Bottom(), Top(). */
Vector3 Center() const;
Vector3 Center() const { return l.CenterPoint();}
Vector3 Centroid() const; ///< [similarOverload: Center]
/// Returns the direction from the bottommost point towards the topmost point of this Capsule.

View File

@@ -36,4 +36,6 @@ namespace J3ML::Geometry
bool operator==(const Interval& rhs) const = default;
};
}
}
using namespace J3ML::Geometry;

View File

@@ -333,13 +333,28 @@ namespace J3ML::Geometry
@see ToPolyhedron(). */
//PBVolume<6> ToPBVolume() const;
Matrix4x4 ViewProjMatrix() const { return viewProjectionMatrix; }
Matrix4x4 ComputeViewProjMatrix() const;
Vector3 Project(const Vector3& point) const {
Vector4 projectedPoint = ViewProjMatrix().Mul(Vector4(point, 1.f));
projectedPoint.NormalizeW();
return projectedPoint.XYZ();
}
/// Tests if the given object is fully contained inside this Frustum.
/** This function returns true if the given object lies inside this Frustum, and false otherwise.
@note The comparison is performed using less-or-equal, so the faces of this Frustum count as being inside, but
due to float inaccuracies, this cannot generally be relied upon.
@todo Add Contains(Circle/Disc/Sphere/Capsule).
@see Distance(), Intersects(), ClosestPoint(). */
bool Contains(const Vector3 &point) const;
bool Contains(const Vector3 &point) const {
const float eps = 1e-3f;
const float position = 1.f + eps;
const float neg = -position;
Vector3 projected = Project(point);
}
bool Contains(const LineSegment &lineSegment) const;
bool Contains(const Triangle &triangle) const;
bool Contains(const Polygon &polygon) const;

View File

@@ -1,12 +1,83 @@
#pragma once
namespace J3ML::Geometry
{
enum CardinalAxis
{
AxisX = 0,
AxisY,
AxisZ,
AxisNone
};
struct KdTreeNode
{
/// If this is an inner node, specifies along which axis this node is split.
/// If this is a leaf, has the value AxisNone.
unsigned splitAxis : 2;
/// If this is an inner node, specifies the index/offset to the child node pair.
/// If this is a leaf, the value is undefined.
unsigned childIndex : 30;
union
{
/// If this is an inner node, specifies the position along the cardinal axis of the split.
float splitPos;
/// If this is a leaf, specifies the index/ofset to the object bucket for this leaf.
/// If zero, this leaf does not have a bucket associated with it. (empty leaf)
u32 bucketIndex;
};
/// If true, this leaf does not contain any objects.
bool IsEmptyLeaf() const { assert(IsLeaf()); return bucketIndex == 0; }
bool IsLeaf() const { return splitAxis == AxisNone; }
int LeftChildIndex() const { return (int)childIndex; }
int RightChildIndex() const { return (int) childIndex+1; }
CardinalAxis SplitAxis() const { return (CardinalAxis) splitAxis;}
};
/// A KD-tree accelleration structure for static geometry.
template <typename T>
class KdTree
{
public:
KdTree() {}
//~KDTree() { /* TODO: FILL */}
void AddObjects(const T *objects, int numObjects);
void Build();
void Clear();
u32* Bucket(int bucketIndex);
const u32* Bucket(int bucketIndex) const;
T& Object(int objectIndex);
const T& Object(int objectIndex) const;
int NumObjects() const;
int NumNodes() const;
int NumLeaves() const;
int NumInnerNodes() const;
int TreeHeight() const;
KdTreeNode* Root();
const KdTreeNode* Root() const;
bool IsPartOfThisTree(const KdTreeNode *node) const;
//const AABB& BoundingAABB() const { return rootAABB;}
/// Traverses a ray through this kD-tree, and calls the given leafCallback function for each leaf of the tree.
/// Uses the "recursive B" method from Vlastimil Havran's thesis.
template <typename Func>
void RayQuery(const Ray& r, Func &leaftCallback);
template <typename Func>
void AABBQuery(const AABB& aabb, Func& leafCallback);
private:
static const int maxNodes = 256 * 1024;
static const int maxTreeDepth = 30;
std::vector<KdTreeNode> nodes;
//std::vector<u8, Aligned
};
}

View File

@@ -1,48 +1,53 @@
#pragma once
#include <J3ML/LinearAlgebra/Vector3.h>
#include "Plane.h"
#include <J3ML/LinearAlgebra/Common.h>
#include <J3ML/Geometry/Common.h>
#include <J3ML/LinearAlgebra/Vector3.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;
/// A line segment in 3D space is a finite line with a start and end point.
class LineSegment
{
public:
Vector3 A;
Vector3 B;
Vector3 A; /// The starting point of this line segment.
Vector3 B; /// The end point of this line segment.
public:
/// The default constructor does not initialize any members of this class.
/** This means that the values of the members A and B are undefined after creating a new LineSegment using this
default constructor. Remember to assign to them before use.
@see A, B. */
LineSegment();
/// Constructs a line segment through the given end points.
/** @see a, b. */
LineSegment(const Vector3& a, const Vector3& b);
/// Computes the closest point on this line segment to the given object.
/** @param d [out] If specified, this parameter receives the normalized distance along
this line segment which specifies the closest point on this line segment to
the specified point.
@return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Vector3 &point) const;
bool Contains(const Vector3& point, float distanceThreshold = 1e-3f) const;
/// Constructs a line segment from a ray or a line.
/** This constructor takes the ray/line origin position as the starting point of this line segment, and defines the end point
of the line segment using the given distance parameter.
@param d The distance along the ray/line for the end point of this line segment. This will set b = ray.pos + d * ray.dir
as the end point. When converting a ray to a line segment, it is possible to pass in a d value < 0, but in that case
the resulting line segment will not lie on the ray.
@see a, b, classes Ray, Line, Line::GetPoint(), Ray::GetPoint() */
explicit LineSegment(const Ray &ray, float d);
explicit LineSegment(const Line &line, float d);
/// Tests if the given point or line segment is contained on this line segment.
/** @param distanceThreshold Because a line segment is an one-dimensional object in 3D space, an epsilon value
is used as a threshold for this test. This effectively transforms this line segment to a capsule with
the radius indicated by this value.
@return True if this line segment contains the given point or line segment.
@see Intersects, ClosestPoint(), Distance(). */
bool Contains(const Vector3& point, float distanceThreshold = 1e-3f) const;
bool Contains(const LineSegment &lineSegment, float distanceThreshold = 1e-3f) const;
/// Quickly returns an arbitrary point inside this LineSegment. Used in GJK intersection test.
inline Vector3 AnyPointFast() const { return A; }
Vector3 AnyPointFast() const;
/// Computes an extreme point of this LineSegment in the given direction.
/** An extreme point is a farthest point along this LineSegment in the given direction. Given a direction,
@@ -52,40 +57,189 @@ namespace J3ML::Geometry
@return An extreme point of this LineSegment in the given direction. The returned point is always
either a or b.
@see a, b.*/
Vector3 ExtremePoint(const Vector3 &direction) const;
[[nodiscard]] Vector3 ExtremePoint(const Vector3 &direction) const;
Vector3 ExtremePoint(const Vector3 &direction, float &projectionDistance) const;
/// Translates this LineSegment in world space.
/** @param offset The amount of displacement to apply to this LineSegment, in world space coordinates.
@see Transform(). */
void Translate(const Vector3 &offset);
/// Applies a transformation to this line.
/** This function operates in-place.
@see Translate(), classes Matrix3x3, Matrix4x4, Quaternion, Transform(). */
void Transform(const Matrix3x3 &transform);
void Transform(const Matrix4x4 &transform);
void Transform(const Quaternion &transform);
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;
/// Returns a point on the line.
/** @param d The normalized distance along the line segment to compute. If a value in the range [0, 1] is passed, then the
returned point lies along this line segment. If some other value is specified, the returned point lies on the
line defined by this line segment, but not inside the interval from a to b.
@note The meaning of d here differs from Line::GetPoint and Ray::GetPoint. For the class LineSegment,
GetPoint(0) returns a, and GetPoint(1) returns b. This means that GetPoint(1) will not generally be exactly one unit
away from the starting point of this line segment, as is the case with Line and Ray.
@return (1-d)*a + d*b.
@see a, b, Line::GetPoint(), Ray::GetPoint(). */
[[nodiscard]] Vector3 GetPoint(float d) const;
float Length() const;
/// Returns the center point of this line segment.
/** This function is the same as calling GetPoint(0.5f), but provided here as conveniency.
@see GetPoint(). */
[[nodiscard]] Vector3 CenterPoint() const;
float LengthSq() const;
/// Reverses the direction of this line segment.
/** This function swaps the start and end points of this line segment so that it runs from b to a.
This does not have an effect on the set of points represented by this line segment, but it reverses
the direction of the vector returned by Dir().
@note This function operates in-place.
@see a, b, Dir(). */
void Reverse();
float DistanceSq(const LineSegment &other) const;
Vector3 ClosestPoint(const LineSegment &other, float &d, float &d2) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Vector3& point) const;
/// Computes the closest point on this line segment to the given object.
/** @param d [out] If specified, this parameter receives the normalized distance along
this line segment which specifies the closest point on this line segment to
the specified point.
@return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Vector3& point, float& d) const;
/** @param d2 [out] If specified, this parameter receives the (normalized, in case of line segment)
distance along the other line object which specifies the closest point on that line to
this line segment. */
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Ray& other) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Ray& other, float &d) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Ray& other, float &d, float &d2) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Line& other) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Line& other, float &d) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const Line &other, float &d, float &d2) const;
bool Intersects(const LineSegment &segment) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const LineSegment& other) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const LineSegment& other, float &d) const;
/// Computes the closest point on this line segment to the given object.
/** @return The closest point on this line segment to the given object.
@see Contains(), Distance(), Intersects(). */
Vector3 ClosestPoint(const LineSegment& other, float &d, float &d2) const;
[[nodiscard]] float Distance(const Vector3 &point) const;
[[nodiscard]] float DistanceSq(const Vector3& point) const;
[[nodiscard]] float DistanceSq(const LineSegment &other) const;
float Distance(const Vector3 &point, float &d) const;
[[nodiscard]] float Distance(const Ray &other) const;
float Distance(const Ray &other, float &d) const;
float Distance(const Ray &other, float &d, float &d2) const;
[[nodiscard]] float Distance(const Line &other) const;
float Distance(const Line &other, float &d) const;
float Distance(const Line &other, float &d, float &d2) const;
[[nodiscard]] float Distance(const LineSegment &other) const;
float Distance(const LineSegment &other, float &d) const;
float Distance(const LineSegment &other, float &d, float &d2) const;
[[nodiscard]] float Distance(const Plane& other) const;
/// Returns the normalized direction vector that points in the direction a->b.
/** @note The returned vector is normalized, meaning that its length is 1, not |b-a|.
@see a, b. */
[[nodiscard]] Vector3 Dir() const;
/// Computes the length of this line segment.
/** @return |b-a|.
@see a, b. */
[[nodiscard]] float Length() const;
/// Computes the squared length of this line segment.
/** Calling this function is faster than calling Length(), since this function avoids computing a square root.
If you only need to compare lengths to each other and are not interested in the actual length values,
you can compare by using LengthSq(), instead of Length(), since Sqrt() is an order-preserving
(monotonous and non-decreasing) function. [similarOverload: Length] */
[[nodiscard]] float LengthSq() const;
/// Tests if this line segment is finite.
/** A line segment is <b><i>finite</i></b> if its endpoints a and b do not contain floating-point NaNs or +/-infs
in them.
@return True if both a and b have finite floating-point values. */
[[nodiscard]] bool IsFinite() const;
/// Tests whether this line segment and the given object intersect.
/** Both objects are treated as "solid", meaning that if one of the objects is fully contained inside
another, this function still returns true. (for example, if this line segment is contained inside a sphere)
@todo Output intersection point. */
bool Intersects(const Plane& plane) const;
bool Intersects(const Plane& plane, float* d) const;
bool Intersects(const Triangle& triangle, float* d, Vector3* intersectionPoint) const;
bool Intersects(const Sphere& s, Vector3* intersectionPoint = 0, Vector3* intersectionNormal = 0, float* d = 0) const;
bool Intersects(const AABB& aabb, float& dNear, float& dFar) const;
bool Intersects(const AABB& aabb) const;
bool Intersects(const OBB& obb, float& dNear, float& dFar) const;
bool Intersects(const OBB& obb) const;
bool Intersects(const Capsule& capsule) const;
bool Intersects(const Polygon& polygon) const;
bool Intersects(const Frustum& frustum) const;
bool Intersects(const Polyhedron& polyhedron) const;
/** @param epsilon If testing intersection between two line segments, a distance threshold value is used to account
for floating-point inaccuracies. */
bool Intersects(const LineSegment &segment, float epsilon = 1e-3f) const;
// TODO: Implement Circle class.
// TODO: This signature will be moved to bool Intersects(const Disc& disc) const;
//bool IntersectsDisc(const Circle& disc) const;
/// Converts this LineSegment to a Ray.
/** The pos member of the returned Ray will be equal to a, and the dir member equal to Dir().
@see class Ray, ToLine() */
[[nodiscard]] Ray ToRay() const;
/// Converts this LineSegment to a Line.
/** The pos member of the returned Line will be equal to a, and the dir member equal to Dir().
@see class Line, ToRay() */
[[nodiscard]] Line ToLine() const;
/// Tests if this line segment represents the same set of points than the given line segment.
/** @param distanceThreshold Specifies how much distance threshold to allow in the comparison.
@return True if a == rhs.a && b == rhs.b, or, a == rhs.b && b = rhs.a, within the given epsilon. */
bool Equals(const LineSegment &rhs, float distanceThreshold = 1e-3f) const;
/// Compares whether this LineSegment and the given LineSegment are identical bit-by-bit in the underlying representation.
/** @note Prefer using this over e.g. memcmp, since there can be SSE-related padding in the structures. */
//bool BitEquals(const LineSegment &other) const { return a.BitEquals(other.a) && b.BitEquals(other.b); }
/// Ret
};
LineSegment operator *(const Matrix4x4 &transform, const LineSegment &l);

View File

@@ -3,7 +3,7 @@
#include <J3ML/Geometry/Common.h>
#include <vector>
#include "Shape.h"
#include "J3ML/LinearAlgebra.h"
#include <J3ML/LinearAlgebra/Common.h>
namespace J3ML::Geometry {
@@ -13,7 +13,7 @@ namespace J3ML::Geometry {
std::vector<Vector3> vertices;
/// Quickly returns an arbitrary point inside this AABB. Used in GJK intersection test.
Vector3 AnyPointFast() const { return !vertices.empty() ? vertices[0] : Vector3::NaN; }
Vector3 AnyPointFast() const;
AABB MinimalEnclosingAABB() const;
int NumVertices() const;

View File

@@ -1,9 +1,33 @@
#pragma once
#include <vector>
#include <J3ML/LinearAlgebra/Common.h>
#include <J3ML/Geometry/Common.h>
#include <J3ML/J3ML.h>
using namespace J3ML::LinearAlgebra;
namespace J3ML::Geometry
{
class TriangleMesh
{
public:
/// Default constructor for a triangle mesh.
TriangleMesh(int expectedPolygonCount = 1000);
public:
//std::vector<Vector3> Vertices;
//std::vector<Vector3> Normals;
//std::vector<Vector3> UVs;
//std::vector<u64> Indices;
std::vector<float> GenerateVertexList();
//std::vector<Triangle> GenerateTriangleList();
private:
std::vector<float> cachedVertexList;
//std::vector<Triangle> cachedTriangleList;
};
}