366 lines
21 KiB
C++
366 lines
21 KiB
C++
#pragma once
|
|
|
|
#include <optional>
|
|
|
|
#include <J3ML/LinearAlgebra.h>
|
|
#include <J3ML/Geometry/Common.h>
|
|
#include <J3ML/Geometry/Shape.h>
|
|
#include "J3ML/Algorithm/RNG.h"
|
|
|
|
|
|
namespace J3ML::Geometry
|
|
{
|
|
using namespace J3ML::LinearAlgebra;
|
|
using J3ML::Algorithm::RNG;
|
|
|
|
/// @brief A 3D axis-aligned bounding box.
|
|
/// This data structure can be used to represent coarse bounds of objects, in situations where detailed triangle-level
|
|
/// computations can be avoided. In physics systems, bounding boxes are used as an efficient early-out test for geometry
|
|
/// intersection queries.
|
|
/// the 'Axis-aligned' part in the name means that the local axes of this bounding box are restricted to align with the
|
|
/// axes of the world space coordinate system. This makes computation involving AABB's very fast, since AABB's cannot
|
|
/// be arbitrarily oriented in the space with respect to each other.
|
|
/// If you need to represent a box in 3D space with arbitrary orientation, see the class OBB. */
|
|
class AABB : public Shape {
|
|
public:
|
|
/// Specifies the minimum extent of this AABB in the world space x, y and z axes.
|
|
Vector3 minPoint;
|
|
/// Specifies the maximum extent of this AABB in the world space x, y and z axes. [similarOverload: minPoint]
|
|
Vector3 maxPoint;
|
|
public:
|
|
static int NumFaces() { return 6; }
|
|
static int NumEdges() { return 12; }
|
|
static int NumVertices() { return 8; }
|
|
public:
|
|
/// The default constructor does not initialize any members of this class.
|
|
/** This means that the values of the members minPoint and maxPoint are undefined after creating a new AABB using this
|
|
default constructor. Remember to assign to them before use.
|
|
@see minPoint, maxPoint. */
|
|
AABB();
|
|
|
|
/// Constructs this AABB by specifying the minimum and maximum extending corners of the box.
|
|
/** @see minPoint, maxPoint. */
|
|
AABB(const Vector3& min, const Vector3& max);
|
|
|
|
/// Constructs this AABB to enclose the given OBB.
|
|
/** This constructor computes the optimal minimum volume AABB that encloses the given OBB.
|
|
@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);
|
|
|
|
/// Constructs this AABB to enclose the given Sphere.
|
|
/** @see class Sphere. */
|
|
explicit AABB(const Sphere &s);
|
|
|
|
Vector3 HalfDiagonal() const { return HalfSize(); }
|
|
|
|
static AABB FromCenterAndSize(const Vector3 ¢er, const Vector3 &size);
|
|
|
|
|
|
/// Returns the minimum world-space coordinate along the given axis.
|
|
float MinX() const;
|
|
float MinY() const; ///< [similarOverload: MinX]
|
|
float MinZ() const; ///< [similarOverload: MinX]
|
|
|
|
/// Returns the maximum world-space coordinate along the given axis.
|
|
float MaxX() const;
|
|
float MaxY() const; ///< [similarOverload: MaxX]
|
|
float MaxZ() const; ///< [similarOverload: MaxX]
|
|
|
|
|
|
Vector3 MinPoint() const;
|
|
|
|
Vector3 MaxPoint() const;
|
|
|
|
/// Returns the smallest sphere that contains this AABB.
|
|
/// This function computes the minimal volume sphere that contains all the points inside this AABB
|
|
Sphere MinimalEnclosingSphere() const;
|
|
|
|
/// [similarOverload: Size]
|
|
/** Returns Size()/2.
|
|
@see Size(), HalfDiagonal(). */
|
|
Vector3 HalfSize() const;
|
|
|
|
/// Returns the largest sphere that can fit inside this AABB
|
|
/// This function computes the largest sphere that can fit inside this AABB.
|
|
Sphere MaximalContainedSphere() const;
|
|
|
|
/// Tests if this AABB is finite.
|
|
/** @return True if the member variables of this AABB are valid floats and do not contain NaNs or infs, and false otherwise.
|
|
@see IsDegenerate(), minPoint, maxPoint. */
|
|
bool IsFinite() const;
|
|
|
|
/// @return The center point of this AABB.
|
|
Vector3 Centroid() const;
|
|
|
|
/// Returns the side lengths of this AABB in x, y and z directions.
|
|
/** The returned vector is equal to the diagonal vector of this AABB, i.e. it spans from the
|
|
minimum corner of the AABB to the maximum corner of the AABB.
|
|
@see HalfSize(), Diagonal(). */
|
|
Vector3 Size() const;
|
|
|
|
// Quickly returns an arbitrary point inside this AABB
|
|
Vector3 AnyPointFast() const;
|
|
|
|
/// Generates a point inside this AABB.
|
|
/** @param x A normalized value between [0,1]. This specifies the point position along the world x axis.
|
|
@param y A normalized value between [0,1]. This specifies the point position along the world y axis.
|
|
@param z A normalized value between [0,1]. This specifies the point position along the world z axis.
|
|
@return A point inside this AABB at point specified by given parameters.
|
|
@see Edge(), CornerPoint(), PointOnEdge(), FaceCenterPoint(), FacePoint(). */
|
|
Vector3 PointInside(float x, float y, float z) const;
|
|
|
|
// Returns an edge of this AABB
|
|
LineSegment Edge(int edgeIndex) const;
|
|
|
|
/// Returns a corner point of this AABB.
|
|
/** This function generates one of the eight corner points of this AABB.
|
|
@param cornerIndex The index of the corner point to generate, in the range [0, 7].
|
|
The points are returned in the order 0: ---, 1: --+, 2: -+-, 3: -++, 4: +--, 5: +-+, 6: ++-, 7: +++. (corresponding the XYZ axis directions).
|
|
@todo Draw which index generates which corner point.
|
|
@see PointInside(), Edge(), PointOnEdge(), FaceCenterPoint(), FacePoint(), GetCornerPoints(). */
|
|
Vector3 CornerPoint(int cornerIndex) const;
|
|
|
|
/// Computes an extreme point of this AABB in the given direction.
|
|
/** An extreme point is a farthest point of this AABB in the given direction. Given a direction,
|
|
this point is not necessarily unique.
|
|
@param direction The direction vector of the direction to find the extreme point. This vector may
|
|
be unnormalized, but may not be null.
|
|
@return An extreme point of this AABB in the given direction. The returned point is always a
|
|
corner point of this AABB.
|
|
@see CornerPoint(). */
|
|
Vector3 ExtremePoint(const Vector3 &direction) const;
|
|
Vector3 ExtremePoint(const Vector3 &direction, float &projectionDistance) const;
|
|
|
|
/// Returns a point on an edge of this AABB.
|
|
/** @param edgeIndex The index of the edge to generate a point to, in the range [0, 11]. @todo Document which index generates which one.
|
|
@param u A normalized value between [0,1]. This specifies the relative distance of the point along the edge.
|
|
@see PointInside(), CornerPoint(), CornerPoint(), FaceCenterPoint(), FacePoint(). */
|
|
Vector3 PointOnEdge(int edgeIndex, float u) const;
|
|
|
|
/// Returns the point at the center of the given face of this AABB.
|
|
/** @param faceIndex The index of the AABB face to generate the point at. The valid range is [0, 5].
|
|
This index corresponds to the planes in the order (-X, +X, -Y, +Y, -Z, +Z).
|
|
@see PointInside(), CornerPoint(), PointOnEdge(), PointOnEdge(), FacePoint(). */
|
|
Vector3 FaceCenterPoint(int faceIndex) const;
|
|
|
|
/// Generates a point at the surface of the given face of this AABB.
|
|
/** @param faceIndex The index of the AABB face to generate the point at. The valid range is [0, 5].
|
|
This index corresponds to the planes in the order (-X, +X, -Y, +Y, -Z, +Z).
|
|
@param u A normalized value between [0, 1].
|
|
@param v A normalized value between [0, 1].
|
|
@see PointInside(), CornerPoint(), PointOnEdge(), PointOnEdge(), FaceCenterPoint(). */
|
|
Vector3 FacePoint(int faceIndex, float u, float v) const;
|
|
|
|
/// Returns the surface normal direction vector the given face points towards.
|
|
/** @param faceIndex The index of the AABB face to generate the point at. The valid range is [0, 5].
|
|
This index corresponds to the planes in the order (-X, +X, -Y, +Y, -Z, +Z).
|
|
@see FacePoint(), FacePlane(). */
|
|
Vector3 FaceNormal(int faceIndex) const;
|
|
|
|
/// Computes the plane equation of the given face of this AABB.
|
|
/** @param faceIndex The index of the AABB face. The valid range is [0, 5].
|
|
This index corresponds to the planes in the order (-X, +X, -Y, +Y, -Z, +Z).
|
|
@return The plane equation the specified face lies on. The normal of this plane points outwards from this AABB.
|
|
@see FacePoint(), FaceNormal(), GetFacePlanes(). */
|
|
Plane FacePlane(int faceIndex) const;
|
|
|
|
|
|
void ProjectToAxis(const Vector3 &direction, float &outMin, float &outMax) const;
|
|
|
|
/// Generates an AABB that encloses the given point set.
|
|
/** This function finds the smallest AABB that contains the given set of points.
|
|
@param pointArray A pointer to an array of points to enclose inside an AABB.
|
|
@param numPoints The number of elements in the pointArray list.
|
|
@see SetFrom(). */
|
|
static AABB MinimalEnclosingAABB(const Vector3 *pointArray, int numPoints);
|
|
AABB MinimalEnclosingAABB() const { return *this;}
|
|
/// Computes the volume of this AABB.
|
|
/** @see SurfaceArea(), IsDegenerate(). */
|
|
float Volume() const;
|
|
/// Computes the surface area of the faces of this AABB.
|
|
/** @see Volume(). */
|
|
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);
|
|
AABB Scaled(const Vector3& scale) const;
|
|
void TransformAABB(const Matrix3x3& transform);
|
|
void TransformAABB(const Matrix4x4& transform);
|
|
void TransformAABB(const Quaternion& transform);
|
|
/// Applies a transformation to this AABB and returns the resulting OBB.
|
|
/** Transforming an AABB produces an oriented bounding box. This set of functions does not apply the transformation
|
|
to this object itself, but instead returns the OBB that results in the transformation.
|
|
@param transform The transformation to apply to this AABB. This function assumes that this
|
|
transformation does not contain shear, nonuniform scaling or perspective properties, i.e. that the fourth
|
|
row of the float4x4 is [0 0 0 1].
|
|
@see Translate(), Scale(), TransformAsAABB(), classes float3x3, float3x4, float4x4, Quat. */
|
|
OBB Transform(const Matrix3x3& transform) const;
|
|
OBB Transform(const Matrix4x4& transform) const;
|
|
OBB Transform(const Quaternion& transform) const;
|
|
|
|
/// Tests if the given object is fully contained inside this AABB.
|
|
/** This function returns true if the given object lies inside this AABB, and false otherwise.
|
|
@note The comparison is performed using less-or-equal, so the faces of this AABB 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& aabbMinPoint, const Vector3& aabbMaxPoint) const;
|
|
bool Contains(const LineSegment& lineSegment) const;
|
|
bool Contains(const AABB& aabb) const;
|
|
bool Contains(const OBB& obb) const;
|
|
bool Contains(const Sphere& sphere) const;
|
|
bool Contains(const Triangle& triangle) const;
|
|
bool Contains(const Polygon& polygon) const;
|
|
bool Contains(const Frustum& frustum) const;
|
|
bool Contains(const Polyhedron& polyhedron) const;
|
|
bool Contains(const Capsule& capsule) const;
|
|
|
|
/// Tests whether this AABB 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. (e.g. in case a line segment is contained inside this AABB,
|
|
or this AABB is contained inside a Sphere, etc.)
|
|
@param ray The first parameter of this function specifies the other object to test against.
|
|
@param dNear [out] If specified, receives the parametric distance along the line denoting where the
|
|
line entered this AABB.
|
|
@param dFar [out] If specified, receives the parametric distance along the line denoting where the
|
|
line exited this AABB.
|
|
@see Contains(), Distance(), ClosestPoint().
|
|
@note If you do not need the intersection intervals, you should call the functions without these
|
|
parameters in the function signature for optimal performance.
|
|
@todo Add Intersects(Circle/Disc). */
|
|
bool Intersects(const Ray& ray, float dNear, float dFar) 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;
|
|
bool Intersects(const AABB& aabb) const;
|
|
|
|
/** For reference documentation on the Sphere-AABB intersection test, see Christer Ericson's Real-Time Collision Detection, p. 165. [groupSyntax]
|
|
@param sphere The first parameter of this function specifies the other object to test against.
|
|
@param closestPointOnAABB [out] Returns the closest point on this AABB to the given sphere. This pointer
|
|
may be null. */
|
|
bool Intersects(const Sphere &sphere, Vector3 *closestPointOnAABB = 0) const;
|
|
|
|
/// Generates an unindexed triangle mesh representation of this AABB.
|
|
/** @param numFacesX The number of faces to generate along the X axis. This value must be >= 1.
|
|
@param numFacesY The number of faces to generate along the Y axis. This value must be >= 1.
|
|
@param numFacesZ The number of faces to generate along the Z axis. This value must be >= 1.
|
|
@param outPos [out] An array of size numVertices which will receive a triangle list
|
|
of vertex positions. Cannot be null.
|
|
@param outNormal [out] An array of size numVertices which will receive vertex normals.
|
|
If this parameter is null, vertex normals are not returned.
|
|
@param outUV [out] An array of size numVertices which will receive vertex UV coordinates.
|
|
If this parameter is null, a UV mapping is not generated.
|
|
@param ccwIsFrontFacing If true, then the front-facing direction of the faces will be the sides
|
|
with counterclockwise winding order. Otherwise, the faces are generated in clockwise winding order.
|
|
The number of vertices that outPos, outNormal and outUV must be able to contain is
|
|
(x*y + x*z + y*z)*2*6. If x==y==z==1, then a total of 36 vertices are required. Call
|
|
NumVerticesInTriangulation to obtain this value.
|
|
@see ToPolyhedron(), ToEdgeList(), NumVerticesInTriangulation(). */
|
|
TriangleMesh Triangulate(int numFacesX, int numFacesY, int numFacesZ, bool ccwIsFrontFacing) const;
|
|
|
|
/// Returns the number of vertices that the Triangulate() function will output with the given subdivision parameters.
|
|
/** @see Triangulate(). */
|
|
static int NumVerticesInTriangulation(int numFacesX, int numFacesY, int numFacesZ)
|
|
{
|
|
return (numFacesX*numFacesY + numFacesX*numFacesZ + numFacesY*numFacesZ)*2*6;
|
|
}
|
|
|
|
/// Returns the number of vertices that the ToEdgeList() function will output.
|
|
/** @see ToEdgeList(). */
|
|
static int NumVerticesInEdgeList()
|
|
{
|
|
return 4*3*2;
|
|
}
|
|
|
|
/// Finds the set intersection of this and the given AABB.
|
|
/** @return This function returns an intersection that is contained in both this and the given AABB if there is one.
|
|
@todo Add Intersection(OBB/Polyhedron). */
|
|
std::optional<AABB> Intersection(const AABB& rhs) const;
|
|
|
|
|
|
/// Sets this AABB to enclose the given set of points.
|
|
/** @param pointArray A pointer to an array of points to enclose inside an AABB.
|
|
@param numPoints The number of elements in the pointArray list.
|
|
@see MinimalEnclosingAABB(). */
|
|
void SetFrom(const Vector3 *pVector3, int i);
|
|
|
|
/// Sets this AABB by specifying its center and size.
|
|
/** @param center The center point of this AABB.
|
|
@param size A vector that specifies the size of this AABB in x, y and z directions.
|
|
@see SetFrom(), FromCenterAndSize(). */
|
|
void SetFromCenterAndSize(const Vector3 ¢er, const Vector3 &size);
|
|
|
|
/// Sets this AABB to enclose the given OBB.
|
|
/** This function computes the minimal axis-aligned bounding box for the given oriented bounding box. If the orientation
|
|
of the OBB is not aligned with the world axes, this conversion is not exact and loosens the volume of the bounding box.
|
|
@param obb The oriented bounding box to convert into this AABB.
|
|
@todo Implement SetFrom(Polyhedron).
|
|
@see SetCenter(), class OBB. */
|
|
void SetFrom(const OBB &obb);
|
|
|
|
/// Sets this AABB to enclose the given sphere.
|
|
/** This function computes the smallest possible AABB (in terms of volume) that contains the given sphere, and stores the result in this structure. */
|
|
void SetFrom(const Sphere &s);
|
|
|
|
Vector3 RandomPointInside(RNG& rng) const;
|
|
Vector3 RandomPointOnSurface(RNG& rng) const;
|
|
Vector3 RandomPointOnEdge(RNG& rng) const;
|
|
Vector3 RandomCornerPoint(RNG& rng) const;
|
|
|
|
/// Sets this structure to a degenerate AABB that does not have any volume.
|
|
/** This function is useful for initializing the AABB to "null" before a loop of calls to Enclose(),
|
|
which incrementally expands the bounds of this AABB to enclose the given objects.
|
|
@see Enclose(). */
|
|
void SetNegativeInfinity();
|
|
|
|
/// Expands this AABB to enclose the given object.
|
|
/** This function computes an AABB that encloses both this AABB and the specified object, and stores the resulting
|
|
AABB into this.
|
|
@note The generated AABB is not necessarily the optimal enclosing AABB for this AABB and the given object. */
|
|
void Enclose(const Vector3 &point);
|
|
void Enclose(const Vector3 &aabbMinPt, const Vector3 &aabbMaxPt);
|
|
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);
|
|
|
|
|
|
bool TestAxis(const Vector3& axis, const Vector3& v0, const Vector3& v1, const Vector3& v2) const;
|
|
|
|
bool Intersects(const LineSegment &lineSegment) const;
|
|
/// Computes the intersection of a line, ray or line segment and an AABB.
|
|
/** Based on "T. Kay, J. Kajiya. Ray Tracing Complex Scenes. SIGGRAPH 1986 vol 20, number 4. pp. 269-"
|
|
http://www.siggraph.org/education/materials/HyperGraph/raytrace/rtinter3.htm
|
|
@param linePos The starting position of the line.
|
|
@param lineDir The direction of the line. This direction vector must be normalized!
|
|
@param tNear [in, out] For the test, the input line is treated as a line segment. Pass in the signed distance
|
|
from the line origin to the start of the line. For a Line-AABB test, -FLOAT_INF is typically passed here.
|
|
For a Ray-AABB test, 0.0f should be inputted. If intersection occurs, the signed distance from line origin
|
|
to the line entry point in the AABB is returned here.
|
|
@param tFar [in, out] Pass in the signed distance from the line origin to the end of the line. For Line-AABB and
|
|
Ray-AABB tests, pass in FLOAT_INF. For a LineSegment-AABB test, pass in the length of the line segment here.
|
|
If intersection occurs, the signed distance from line origin to the line exit point in the AABB
|
|
is returned here.
|
|
@return True if an intersection occurs, false otherwise.
|
|
@note This is a low level utility function. It may be more convenient to use one of the AABB::Intersects()
|
|
functions instead.
|
|
@see Intersects(). */
|
|
bool IntersectLineAABB(const Vector3& linePos, const Vector3& lineDir, float tNear, float tFar) const;
|
|
bool IntersectLineAABB_CPP(const Vector3 &linePos, const Vector3 &lineDir, float &tNear, float &tFar) const;
|
|
};
|
|
|
|
|
|
}
|