Typedefs | |
template<typename Real > | |
using | AlignedBox2 = AlignedBox< 2, Real > |
template<typename Real > | |
using | AlignedBox3 = AlignedBox< 3, Real > |
typedef std::vector< MemberLayout > | BufferLayout |
typedef std::function< void(std::shared_ptr< Buffer > const &)> | BufferUpdater |
template<typename Real > | |
using | Capsule3 = Capsule< 3, Real > |
template<typename Real > | |
using | Circle2 = Hypersphere< 2, Real > |
template<typename Real > | |
using | Cone3 = Cone< 3, Real > |
template<typename Real > | |
using | DCPLine2Line2 = DCPLineLine< 2, Real > |
template<typename Real > | |
using | DCPLine2Ray2 = DCPLineRay< 2, Real > |
template<typename Real > | |
using | DCPLine2Segment2 = DCPLineSegment< 2, Real > |
template<typename Real > | |
using | DCPLine3Line3 = DCPLineLine< 3, Real > |
template<typename Real > | |
using | DCPLine3Ray3 = DCPLineRay< 3, Real > |
template<typename Real > | |
using | DCPLine3Rectangle3 = DCPQuery< Real, Line3< Real >, Rectangle3< Real >> |
template<typename Real > | |
using | DCPLine3Segment3 = DCPLineSegment< 3, Real > |
template<int N, typename Real > | |
using | DCPLineLine = DCPQuery< Real, Line< N, Real >, Line< N, Real >> |
template<int N, typename Real > | |
using | DCPLineRay = DCPQuery< Real, Line< N, Real >, Ray< N, Real >> |
template<int N, typename Real > | |
using | DCPLineSegment = DCPQuery< Real, Line< N, Real >, Segment< N, Real >> |
template<typename Real > | |
using | DCPPoint2AlignedBox2 = DCPPointAlignedBox< 2, Real > |
template<typename Real > | |
using | DCPPoint2Ellipse2 = DCPPointHyperellipsoid< 2, Real > |
template<typename Real > | |
using | DCPPoint2Line2 = DCPPointLine< 2, Real > |
template<typename Real > | |
using | DCPPoint2OrientedBox2 = DCPPointOrientedBox< 2, Real > |
template<typename Real > | |
using | DCPPoint2Ray2 = DCPPointRay< 2, Real > |
template<typename Real > | |
using | DCPPoint2Segment2 = DCPPointSegment< 2, Real > |
template<typename Real > | |
using | DCPPoint2Triangle2 = DCPPointTriangle< 2, Real > |
template<typename Real > | |
using | DCPPoint3AlignedBox3 = DCPPointAlignedBox< 3, Real > |
template<typename Real > | |
using | DCPPoint3Ellipsoid3 = DCPPointHyperellipsoid< 3, Real > |
template<typename Real > | |
using | DCPPoint3Line3 = DCPPointLine< 3, Real > |
template<typename Real > | |
using | DCPPoint3OrientedBox3 = DCPPointOrientedBox< 3, Real > |
template<typename Real > | |
using | DCPPoint3Ray3 = DCPPointRay< 3, Real > |
template<typename Real > | |
using | DCPPoint3Segment3 = DCPPointSegment< 3, Real > |
template<typename Real > | |
using | DCPPoint3Triangle3 = DCPPointTriangle< 3, Real > |
template<int N, typename Real > | |
using | DCPPointAlignedBox = DCPQuery< Real, Vector< N, Real >, AlignedBox< N, Real >> |
template<int N, typename Real > | |
using | DCPPointHyperellipsoid = DCPQuery< Real, Vector< N, Real >, Hyperellipsoid< N, Real >> |
template<int N, typename Real > | |
using | DCPPointLine = DCPQuery< Real, Vector< N, Real >, Line< N, Real >> |
template<int N, typename Real > | |
using | DCPPointOrientedBox = DCPQuery< Real, Vector< N, Real >, AlignedBox< N, Real >> |
template<int N, typename Real > | |
using | DCPPointRay = DCPQuery< Real, Vector< N, Real >, Ray< N, Real >> |
template<int N, typename Real > | |
using | DCPPointSegment = DCPQuery< Real, Vector< N, Real >, Segment< N, Real >> |
template<int N, typename Real > | |
using | DCPPointTriangle = DCPQuery< Real, Vector< N, Real >, Triangle< N, Real >> |
template<typename Real > | |
using | DCPRay2Ray2 = DCPRayRay< 2, Real > |
template<typename Real > | |
using | DCPRay2Segment2 = DCPRaySegment< 2, Real > |
template<typename Real > | |
using | DCPRay3Ray3 = DCPRayRay< 3, Real > |
template<typename Real > | |
using | DCPRay3Segment3 = DCPRaySegment< 3, Real > |
template<int N, typename Real > | |
using | DCPRayRay = DCPQuery< Real, Ray< N, Real >, Ray< N, Real >> |
template<int N, typename Real > | |
using | DCPRaySegment = DCPQuery< Real, Ray< N, Real >, Segment< N, Real >> |
template<typename Real > | |
using | DCPSegment2Segment2 = DCPSegmentSegment< 2, Real > |
template<typename Real > | |
using | DCPSegment3Segment3 = DCPSegmentSegment< 3, Real > |
template<int N, typename Real > | |
using | DCPSegmentSegment = DCPQuery< Real, Segment< N, Real >, Segment< N, Real >> |
template<typename Real > | |
using | Ellipse2 = Hyperellipsoid< 2, Real > |
template<typename Real > | |
using | Ellipsoid3 = Hyperellipsoid< 3, Real > |
template<typename Real > | |
using | FIEllipses2 = FIQuery< Real, Ellipse2< Real >, Ellipse2< Real >> |
template<typename Real > | |
using | FIIntervalInterval = FIQuery< Real, std::array< Real, 2 >, std::array< Real, 2 >> |
template<typename Real > | |
using | Halfspace3 = Halfspace< 3, Real > |
typedef IEEEBinary< float, uint32_t, 32, 24 > | IEEEBinary32 |
typedef IEEEBinary< double, uint64_t, 64, 53 > | IEEEBinary64 |
template<typename Real > | |
using | Line2 = Line< 2, Real > |
template<typename Real > | |
using | Line3 = Line< 3, Real > |
template<typename Real > | |
using | Matrix2x2 = Matrix< 2, 2, Real > |
template<typename Real > | |
using | Matrix3x3 = Matrix< 3, 3, Real > |
template<typename Real > | |
using | Matrix4x4 = Matrix< 4, 4, Real > |
template<typename Real > | |
using | OrientedBox2 = OrientedBox< 2, Real > |
template<typename Real > | |
using | OrientedBox3 = OrientedBox< 3, Real > |
template<typename Real > | |
using | Plane3 = Hyperplane< 3, Real > |
template<typename Real > | |
using | Ray2 = Ray< 2, Real > |
template<typename Real > | |
using | Ray3 = Ray< 3, Real > |
template<typename Real > | |
using | Rectangle3 = Rectangle< 3, Real > |
template<typename Real > | |
using | Segment2 = Segment< 2, Real > |
template<typename Real > | |
using | Segment3 = Segment< 3, Real > |
template<typename Real > | |
using | Sphere3 = Hypersphere< 3, Real > |
typedef std::function< void(std::shared_ptr< TextureArray > const &, unsigned int)> | TextureArrayLevelUpdater |
typedef std::function< void(std::shared_ptr< TextureArray > const &)> | TextureArrayUpdater |
typedef std::function< void(std::shared_ptr< Texture > const &, unsigned int)> | TextureLevelUpdater |
typedef std::function< void(std::shared_ptr< Texture > const &)> | TextureUpdater |
template<typename Real > | |
using | TIAlignedBox3Cone3 = TIQuery< Real, AlignedBox< 3, Real >, Cone< 3, Real >> |
template<typename Real > | |
using | TIEllipses2 = TIQuery< Real, Ellipse2< Real >, Ellipse2< Real >> |
template<typename Real > | |
using | TIIntervalInterval = TIQuery< Real, std::array< Real, 2 >, std::array< Real, 2 >> |
template<typename Real > | |
using | TIOrientedBox3Cone3 = TIQuery< Real, OrientedBox< 3, Real >, Cone< 3, Real >> |
template<typename Real > | |
using | Triangle2 = Triangle< 2, Real > |
template<typename Real > | |
using | Triangle3 = Triangle< 3, Real > |
template<typename Real > | |
using | Vector2 = Vector< 2, Real > |
template<typename Real > | |
using | Vector3 = Vector< 3, Real > |
template<typename Real > | |
using | Vector4 = Vector< 4, Real > |
typedef std::vector< Visual * > | VisibleSet |
Functions | |
template<typename Real > | |
Matrix3x3< Real > | Adjoint (Matrix3x3< Real > const &M) |
template<typename Real > | |
Matrix4x4< Real > | Adjoint (Matrix4x4< Real > const &M) |
template<typename Real > | |
Matrix2x2< Real > | Adjoint (Matrix2x2< Real > const &M) |
template<typename Real > | |
bool | ApproximateEllipseByArcs (Real a, Real b, int numArcs, std::vector< Vector2< Real >> &points, std::vector< Vector2< Real >> ¢ers, std::vector< Real > &radii) |
template<typename T > | |
T | AtomicMax (std::atomic< T > &v0, T const &v1) |
template<typename T > | |
T | AtomicMin (std::atomic< T > &v0, T const &v1) |
template<typename Real > | |
bool | Circumscribe (Vector2< Real > const &v0, Vector2< Real > const &v1, Vector2< Real > const &v2, Circle2< Real > &circle) |
template<typename Real > | |
bool | Circumscribe (Vector3< Real > const &v0, Vector3< Real > const &v1, Vector3< Real > const &v2, Circle3< Real > &circle) |
template<typename Real > | |
bool | Circumscribe (Vector3< Real > const &v0, Vector3< Real > const &v1, Vector3< Real > const &v2, Vector3< Real > const &v3, Sphere3< Real > &sphere) |
template<typename Real > | |
bool | ComputeBarycentrics (Vector2< Real > const &p, Vector2< Real > const &v0, Vector2< Real > const &v1, Vector2< Real > const &v2, Real bary[3], Real epsilon=(Real) 0) |
template<typename Real > | |
bool | ComputeBarycentrics (Vector3< Real > const &p, Vector3< Real > const &v0, Vector3< Real > const &v1, Vector3< Real > const &v2, Vector3< Real > const &v3, Real bary[4], Real epsilon=(Real) 0) |
template<typename Real > | |
bool | ComputeExtremes (int numVectors, GVector< Real > const *v, GVector< Real > &vmin, GVector< Real > &vmax) |
template<int N, typename Real > | |
bool | ComputeExtremes (int numVectors, Vector< N, Real > const *v, Vector< N, Real > &vmin, Vector< N, Real > &vmax) |
template<typename Real > | |
void | ComputeMassProperties (Vector3< Real > const *vertices, int numTriangles, int const *indices, bool bodyCoords, Real &mass, Vector3< Real > ¢er, Matrix3x3< Real > &inertia) |
template<typename Real > | |
Real | ComputeOrthogonalComplement (int numInputs, Vector2< Real > *v, bool robust=false) |
template<typename Real > | |
Real | ComputeOrthogonalComplement (int numInputs, Vector3< Real > *v, bool robust=false) |
template<typename Real > | |
Real | ComputeOrthogonalComplement (int numInputs, Vector4< Real > *v, bool robust=false) |
template<typename Real > | |
Quaternion< Real > | Conjugate (Quaternion< Real > const &q) |
template<typename Real > | |
DualQuaternion< Real > | Conjugate (DualQuaternion< Real > const &d) |
template<int N, typename Real > | |
Vector< N, Real > | Cross (Vector< N, Real > const &v0, Vector< N, Real > const &v1) |
template<int N, typename Real > | |
DualQuaternion< Real > | Cross (DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1) |
template<typename Real > | |
Real | Determinant (Matrix3x3< Real > const &M) |
template<typename Real > | |
Real | Determinant (Matrix4x4< Real > const &M) |
template<typename Real > | |
Real | Determinant (Matrix2x2< Real > const &M) |
template<typename Real > | |
Real | Determinant (GMatrix< Real > const &M) |
template<int N, typename Real > | |
Real | Determinant (Matrix< N, N, Real > const &M) |
template<typename Real > | |
Real | Dot (GVector< Real > const &v0, GVector< Real > const &v1) |
template<int N, typename Real > | |
Real | Dot (Vector< N, Real > const &v0, Vector< N, Real > const &v1) |
template<int N, typename Real > | |
DualQuaternion< Real > | Dot (DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1) |
template<int N, typename Real > | |
Real | DotCross (Vector< N, Real > const &v0, Vector< N, Real > const &v1, Vector< N, Real > const &v2) |
template<typename Real > | |
Real | DotHyperCross (Vector4< Real > const &v0, Vector4< Real > const &v1, Vector4< Real > const &v2, Vector4< Real > const &v3) |
template<typename Real > | |
Real | DotPerp (Vector2< Real > const &v0, Vector2< Real > const &v1) |
template<typename T > | |
ULONG | FinalRelease (T *&object) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector2< Real > const *points, Circle2< Real > &circle) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector2< Real > const *points, OrientedBox2< Real > &box) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector3< Real > const *points, Sphere3< Real > &sphere) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector3< Real > const *points, Cylinder3< Real > &cylinder) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector3< Real > const *points, OrientedBox3< Real > &box) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector3< Real > const *points, Capsule3< Real > &capsule) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector2< Real > const *points, Ellipse2< Real > &ellipse) |
template<typename Real > | |
bool | GetContainer (int numPoints, Vector3< Real > const *points, Ellipsoid3< Real > &ellipsoid) |
GTE_IMPEXP int32_t | GetLeadingBit (uint32_t value) |
GTE_IMPEXP int32_t | GetLeadingBit (int32_t value) |
GTE_IMPEXP int32_t | GetLeadingBit (uint64_t value) |
GTE_IMPEXP int32_t | GetLeadingBit (int64_t value) |
template<int N, typename Real > | |
Vector< N, Real > | GetOrthogonal (Vector< N, Real > const &v, bool unitLength) |
template<typename Real > | |
Real | GetRotationAngle (Matrix2x2< Real > const &rotation) |
GTE_IMPEXP int32_t | GetTrailingBit (uint32_t value) |
GTE_IMPEXP int32_t | GetTrailingBit (int32_t value) |
GTE_IMPEXP int32_t | GetTrailingBit (uint64_t value) |
GTE_IMPEXP int32_t | GetTrailingBit (int64_t value) |
template<typename Real > | |
GVector< Real > | HLift (GVector< Real > const &v, Real last) |
template<int N, typename Real > | |
Vector< N+1, Real > | HLift (Vector< N, Real > const &v, Real last) |
template<int N, typename Real > | |
Matrix< N+1, N+1, Real > | HLift (Matrix< N, N, Real > const &M) |
template<typename Real > | |
GVector< Real > | HProject (GVector< Real > const &v) |
template<int N, typename Real > | |
Vector< N-1, Real > | HProject (Vector< N, Real > const &v) |
template<int N, typename Real > | |
Matrix< N-1, N-1, Real > | HProject (Matrix< N, N, Real > const &M) |
template<typename Real > | |
Vector4< Real > | HyperCross (Vector4< Real > const &v0, Vector4< Real > const &v1, Vector4< Real > const &v2) |
template<typename Real > | |
bool | InContainer (Vector2< Real > const &point, Circle2< Real > const &circle) |
template<typename Real > | |
bool | InContainer (Vector3< Real > const &point, Sphere3< Real > const &sphere) |
template<typename Real > | |
bool | InContainer (Vector3< Real > const &point, Cylinder3< Real > const &cylinder) |
template<typename Real > | |
bool | InContainer (Vector2< Real > const &point, OrientedBox2< Real > const &box) |
template<typename Real > | |
bool | InContainer (Vector3< Real > const &point, OrientedBox3< Real > const &box) |
template<typename Real > | |
bool | InContainer (Vector3< Real > const &point, Capsule3< Real > const &capsule) |
template<typename Real > | |
bool | InContainer (Vector2< Real > const &point, Ellipse2< Real > const &ellipse) |
template<typename Real > | |
bool | InContainer (Sphere3< Real > const &sphere, Capsule3< Real > const &capsule) |
template<typename Real > | |
bool | InContainer (Vector3< Real > const &point, Ellipsoid3< Real > const &ellipsoid) |
template<typename Real > | |
bool | InContainer (Capsule3< Real > const &testCapsule, Capsule3< Real > const &capsule) |
template<typename Real > | |
bool | Inscribe (Vector2< Real > const &v0, Vector2< Real > const &v1, Vector2< Real > const &v2, Circle2< Real > &circle) |
template<typename Real > | |
bool | Inscribe (Vector3< Real > const &v0, Vector3< Real > const &v1, Vector3< Real > const &v2, Circle3< Real > &circle) |
template<typename Real > | |
bool | Inscribe (Vector3< Real > const &v0, Vector3< Real > const &v1, Vector3< Real > const &v2, Vector3< Real > const &v3, Sphere3< Real > &sphere) |
template<typename Real > | |
Matrix3x3< Real > | Inverse (Matrix3x3< Real > const &M, bool *reportInvertibility=nullptr) |
template<typename Real > | |
Matrix4x4< Real > | Inverse (Matrix4x4< Real > const &M, bool *reportInvertibility=nullptr) |
template<typename Real > | |
Matrix2x2< Real > | Inverse (Matrix2x2< Real > const &M, bool *reportInvertibility=nullptr) |
template<typename Real > | |
GMatrix< Real > | Inverse (GMatrix< Real > const &M, bool *reportInvertibility=nullptr) |
template<int N, typename Real > | |
Matrix< N, N, Real > | Inverse (Matrix< N, N, Real > const &M, bool *reportInvertibility=nullptr) |
template<typename Real > | |
Quaternion< Real > | Inverse (Quaternion< Real > const &d) |
GTE_IMPEXP bool | IsPowerOfTwo (uint32_t value) |
GTE_IMPEXP bool | IsPowerOfTwo (int32_t value) |
template<typename Real > | |
Real | L1Norm (GMatrix< Real > const &M) |
template<int NumRows, int NumCols, typename Real > | |
Real | L1Norm (Matrix< NumRows, NumCols, Real > const &M) |
template<typename Real > | |
Real | L2Norm (GMatrix< Real > const &M) |
template<int NumRows, int NumCols, typename Real > | |
Real | L2Norm (Matrix< NumRows, NumCols, Real > const &M) |
template<typename Real > | |
Real | Length (GVector< Real > const &v, bool robust=false) |
template<int N, typename Real > | |
Real | Length (Vector< N, Real > const &v, bool robust=false) |
template<int N, typename Real > | |
DualQuaternion< Real > | Length (DualQuaternion< Real > const &d, bool robust=false) |
template<typename Real > | |
GVector< Real > | Lift (GVector< Real > const &v, int inject, Real value) |
template<int N, typename Real > | |
Vector< N+1, Real > | Lift (Vector< N, Real > const &v, int inject, Real value) |
template<typename Real > | |
Real | LInfinityNorm (GMatrix< Real > const &M) |
template<int NumRows, int NumCols, typename Real > | |
Real | LInfinityNorm (Matrix< NumRows, NumCols, Real > const &M) |
GTE_IMPEXP uint32_t | Log2OfPowerOfTwo (uint32_t powerOfTwo) |
GTE_IMPEXP int32_t | Log2OfPowerOfTwo (int32_t powerOfTwo) |
template<typename Real > | |
void | MakeDiagonal (GVector< Real > const &D, GMatrix< Real > &M) |
template<int N, typename Real > | |
void | MakeDiagonal (Vector< N, Real > const &D, Matrix< N, N, Real > &M) |
template<typename Real > | |
Matrix4x4< Real > | MakeObliqueProjection (Vector4< Real > const &origin, Vector4< Real > const &normal, Vector4< Real > const &direction) |
template<typename Real > | |
Matrix4x4< Real > | MakePerspectiveProjection (Vector4< Real > const &origin, Vector4< Real > const &normal, Vector4< Real > const &eye) |
template<typename Real > | |
Matrix4x4< Real > | MakeReflection (Vector4< Real > const &origin, Vector4< Real > const &normal) |
template<typename Real > | |
void | MakeRotation (Real angle, Matrix2x2< Real > &rotation) |
void | Memcpy (void *target, void const *source, size_t count) |
void | Memcpy (wchar_t *target, wchar_t const *source, size_t count) |
template<typename Real > | |
bool | MergeContainers (Circle2< Real > const &circle0, Circle2< Real > const &circle1, Circle2< Real > &merge) |
template<typename Real > | |
bool | MergeContainers (Sphere3< Real > const &sphere0, Sphere3< Real > const &sphere1, Sphere3< Real > &merge) |
template<typename Real > | |
bool | MergeContainers (OrientedBox2< Real > const &box0, OrientedBox2< Real > const &box1, OrientedBox2< Real > &merge) |
template<typename Real > | |
bool | MergeContainers (OrientedBox3< Real > const &box0, OrientedBox3< Real > const &box1, OrientedBox3< Real > &merge) |
template<typename Real > | |
bool | MergeContainers (Ellipse2< Real > const &ellipse0, Ellipse2< Real > const &ellipse1, Ellipse2< Real > &merge) |
template<typename Real > | |
bool | MergeContainers (Ellipsoid3< Real > const &ellipsoid0, Ellipsoid3< Real > const &ellipsoid1, Ellipsoid3< Real > &merge) |
template<typename Real > | |
bool | MergeContainers (Capsule3< Real > const &capsule0, Capsule3< Real > const &capsule1, Capsule3< Real > &merge) |
template<typename Real > | |
GMatrix< Real > | MultiplyAB (GMatrix< Real > const &A, GMatrix< Real > const &B) |
template<int NumRows, int NumCols, int NumCommon, typename Real > | |
Matrix< NumRows, NumCols, Real > | MultiplyAB (Matrix< NumRows, NumCommon, Real > const &A, Matrix< NumCommon, NumCols, Real > const &B) |
template<typename Real > | |
GMatrix< Real > | MultiplyABT (GMatrix< Real > const &A, GMatrix< Real > const &B) |
template<int NumRows, int NumCols, int NumCommon, typename Real > | |
Matrix< NumRows, NumCols, Real > | MultiplyABT (Matrix< NumRows, NumCommon, Real > const &A, Matrix< NumCols, NumCommon, Real > const &B) |
template<typename Real > | |
GMatrix< Real > | MultiplyATB (GMatrix< Real > const &A, GMatrix< Real > const &B) |
template<int NumRows, int NumCols, int NumCommon, typename Real > | |
Matrix< NumRows, NumCols, Real > | MultiplyATB (Matrix< NumCommon, NumRows, Real > const &A, Matrix< NumCommon, NumCols, Real > const &B) |
template<typename Real > | |
GMatrix< Real > | MultiplyATBT (GMatrix< Real > const &A, GMatrix< Real > const &B) |
template<int NumRows, int NumCols, int NumCommon, typename Real > | |
Matrix< NumRows, NumCols, Real > | MultiplyATBT (Matrix< NumCommon, NumRows, Real > const &A, Matrix< NumCols, NumCommon, Real > const &B) |
template<typename Real > | |
GMatrix< Real > | MultiplyDM (GVector< Real > const &D, GMatrix< Real > const &M) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | MultiplyDM (Vector< NumRows, Real > const &D, Matrix< NumRows, NumCols, Real > const &M) |
template<typename Real > | |
GMatrix< Real > | MultiplyMD (GMatrix< Real > const &M, GVector< Real > const &D) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | MultiplyMD (Matrix< NumRows, NumCols, Real > const &M, Vector< NumCols, Real > const &D) |
template<int N, typename Real > | |
DualQuaternion< Real > | Norm (DualQuaternion< Real > &d, bool robust=false) |
template<typename Real > | |
Real | Normalize (GVector< Real > &v, bool robust=false) |
template<int N, typename Real > | |
Real | Normalize (Vector< N, Real > &v, bool robust=false) |
template<typename Real > | |
Quaternion< Real > | operator* (Quaternion< Real > const &q0, Quaternion< Real > const &q1) |
float | operator* (IEEEBinary16 x, IEEEBinary16 y) |
float | operator* (IEEEBinary16 x, float y) |
float | operator* (float x, IEEEBinary16 y) |
template<typename Real > | |
GVector< Real > | operator* (GVector< Real > const &v, Real scalar) |
template<typename Real > | |
GVector< Real > | operator* (Real scalar, GVector< Real > const &v) |
template<int N, typename Real > | |
Vector< N, Real > | operator* (Vector< N, Real > const &v, Real scalar) |
template<int N, typename Real > | |
Vector< N, Real > | operator* (Real scalar, Vector< N, Real > const &v) |
template<typename Real > | |
Polynomial1< Real > | operator* (Polynomial1< Real > const &p0, Polynomial1< Real > const &p1) |
template<typename Real > | |
GMatrix< Real > | operator* (GMatrix< Real > const &M, Real scalar) |
template<typename Real > | |
GMatrix< Real > | operator* (Real scalar, GMatrix< Real > const &M) |
template<int N, typename Real > | |
Vector< N, Real > | operator* (Vector< N, Real > const &v0, Vector< N, Real > const &v1) |
template<typename Real > | |
Polynomial1< Real > | operator* (Polynomial1< Real > const &p, Real scalar) |
template<typename Real > | |
Polynomial1< Real > | operator* (Real scalar, Polynomial1< Real > const &p) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator* (Matrix< NumRows, NumCols, Real > const &M, Real scalar) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator* (Real scalar, Matrix< NumRows, NumCols, Real > const &M) |
template<typename Real > | |
GVector< Real > | operator* (GMatrix< Real > const &M, GVector< Real > const &V) |
template<typename Real > | |
GVector< Real > | operator* (GVector< Real > const &V, GMatrix< Real > const &M) |
template<typename Real > | |
GMatrix< Real > | operator* (GMatrix< Real > const &A, GMatrix< Real > const &B) |
Vector4< float > | operator* (Transform const &M, Vector4< float > const &V) |
Vector4< float > | operator* (Vector4< float > const &V, Transform const &M) |
Transform | operator* (Transform const &A, Transform const &B) |
template<int NumRows, int NumCols, typename Real > | |
Vector< NumRows, Real > | operator* (Matrix< NumRows, NumCols, Real > const &M, Vector< NumCols, Real > const &V) |
Matrix4x4< float > | operator* (Matrix4x4< float > const &A, Transform const &B) |
Matrix4x4< float > | operator* (Transform const &A, Matrix4x4< float > const &B) |
template<int NumRows, int NumCols, typename Real > | |
Vector< NumCols, Real > | operator* (Vector< NumRows, Real > const &V, Matrix< NumRows, NumCols, Real > const &M) |
template<int NumRows, int NumCols, int NumCommon, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator* (Matrix< NumRows, NumCommon, Real > const &A, Matrix< NumCommon, NumCols, Real > const &B) |
template<typename Real > | |
DualQuaternion< Real > | operator* (DualQuaternion< Real > const &d, Real scalar) |
template<typename Real > | |
DualQuaternion< Real > | operator* (Real scalar, DualQuaternion< Real > const &d) |
template<typename Real > | |
DualQuaternion< Real > | operator* (DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1) |
IEEEBinary16 & | operator*= (IEEEBinary16 &x, IEEEBinary16 y) |
IEEEBinary16 & | operator*= (IEEEBinary16 &x, float y) |
template<typename Real > | |
GVector< Real > & | operator*= (GVector< Real > &v, Real scalar) |
template<int N, typename Real > | |
Vector< N, Real > & | operator*= (Vector< N, Real > &v, Real scalar) |
template<int N, typename Real > | |
Vector< N, Real > & | operator*= (Vector< N, Real > &v0, Vector< N, Real > const &v1) |
template<typename Real > | |
GMatrix< Real > & | operator*= (GMatrix< Real > &M, Real scalar) |
template<typename Real > | |
Polynomial1< Real > & | operator*= (Polynomial1< Real > &p0, Polynomial1< Real > const &p1) |
template<typename Real > | |
Polynomial1< Real > & | operator*= (Polynomial1< Real > &p, Real scalar) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > & | operator*= (Matrix< NumRows, NumCols, Real > &M, Real scalar) |
template<typename Real > | |
DualQuaternion< Real > & | operator*= (DualQuaternion< Real > &d, Real scalar) |
template<typename Real > | |
GVector< Real > | operator+ (GVector< Real > const &v) |
template<int N, typename Real > | |
Vector< N, Real > | operator+ (Vector< N, Real > const &v) |
float | operator+ (IEEEBinary16 x, IEEEBinary16 y) |
float | operator+ (IEEEBinary16 x, float y) |
template<typename Real > | |
GVector< Real > | operator+ (GVector< Real > const &v0, GVector< Real > const &v1) |
template<int N, typename Real > | |
Vector< N, Real > | operator+ (Vector< N, Real > const &v0, Vector< N, Real > const &v1) |
float | operator+ (float x, IEEEBinary16 y) |
template<typename Real > | |
Polynomial1< Real > | operator+ (Polynomial1< Real > const &p) |
template<typename Real > | |
GMatrix< Real > | operator+ (GMatrix< Real > const &M) |
template<typename Real > | |
Polynomial1< Real > | operator+ (Polynomial1< Real > const &p0, Polynomial1< Real > const &p1) |
template<typename Real > | |
GMatrix< Real > | operator+ (GMatrix< Real > const &M0, GMatrix< Real > const &M1) |
template<typename Real > | |
Polynomial1< Real > | operator+ (Polynomial1< Real > const &p, Real scalar) |
template<typename Real > | |
Polynomial1< Real > | operator+ (Real scalar, Polynomial1< Real > const &p) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator+ (Matrix< NumRows, NumCols, Real > const &M) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator+ (Matrix< NumRows, NumCols, Real > const &M0, Matrix< NumRows, NumCols, Real > const &M1) |
template<typename Real > | |
DualQuaternion< Real > | operator+ (DualQuaternion< Real > const &d) |
template<typename Real > | |
DualQuaternion< Real > | operator+ (DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1) |
IEEEBinary16 & | operator+= (IEEEBinary16 &x, IEEEBinary16 y) |
IEEEBinary16 & | operator+= (IEEEBinary16 &x, float y) |
template<typename Real > | |
GVector< Real > & | operator+= (GVector< Real > &v0, GVector< Real > const &v1) |
template<int N, typename Real > | |
Vector< N, Real > & | operator+= (Vector< N, Real > &v0, Vector< N, Real > const &v1) |
template<typename Real > | |
GMatrix< Real > & | operator+= (GMatrix< Real > &M0, GMatrix< Real > const &M1) |
template<typename Real > | |
Polynomial1< Real > & | operator+= (Polynomial1< Real > &p0, Polynomial1< Real > const &p1) |
template<typename Real > | |
Polynomial1< Real > & | operator+= (Polynomial1< Real > &p, Real scalar) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > & | operator+= (Matrix< NumRows, NumCols, Real > &M0, Matrix< NumRows, NumCols, Real > const &M1) |
template<typename Real > | |
DualQuaternion< Real > & | operator+= (DualQuaternion< Real > &d0, DualQuaternion< Real > const &d1) |
IEEEBinary16 | operator- (IEEEBinary16 x) |
float | operator- (IEEEBinary16 x, IEEEBinary16 y) |
template<typename Real > | |
GVector< Real > | operator- (GVector< Real > const &v) |
template<int N, typename Real > | |
Vector< N, Real > | operator- (Vector< N, Real > const &v) |
float | operator- (IEEEBinary16 x, float y) |
template<typename Real > | |
GVector< Real > | operator- (GVector< Real > const &v0, GVector< Real > const &v1) |
float | operator- (float x, IEEEBinary16 y) |
template<int N, typename Real > | |
Vector< N, Real > | operator- (Vector< N, Real > const &v0, Vector< N, Real > const &v1) |
template<typename Real > | |
Polynomial1< Real > | operator- (Polynomial1< Real > const &p) |
template<typename Real > | |
GMatrix< Real > | operator- (GMatrix< Real > const &M) |
template<typename Real > | |
Polynomial1< Real > | operator- (Polynomial1< Real > const &p0, Polynomial1< Real > const &p1) |
template<typename Real > | |
GMatrix< Real > | operator- (GMatrix< Real > const &M0, GMatrix< Real > const &M1) |
template<typename Real > | |
Polynomial1< Real > | operator- (Polynomial1< Real > const &p, Real scalar) |
template<typename Real > | |
Polynomial1< Real > | operator- (Real scalar, Polynomial1< Real > const &p) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator- (Matrix< NumRows, NumCols, Real > const &M) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator- (Matrix< NumRows, NumCols, Real > const &M0, Matrix< NumRows, NumCols, Real > const &M1) |
template<typename Real > | |
DualQuaternion< Real > | operator- (DualQuaternion< Real > const &d) |
template<typename Real > | |
DualQuaternion< Real > | operator- (DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1) |
IEEEBinary16 & | operator-= (IEEEBinary16 &x, IEEEBinary16 y) |
IEEEBinary16 & | operator-= (IEEEBinary16 &x, float y) |
template<typename Real > | |
GVector< Real > & | operator-= (GVector< Real > &v0, GVector< Real > const &v1) |
template<int N, typename Real > | |
Vector< N, Real > & | operator-= (Vector< N, Real > &v0, Vector< N, Real > const &v1) |
template<typename Real > | |
GMatrix< Real > & | operator-= (GMatrix< Real > &M0, GMatrix< Real > const &M1) |
template<typename Real > | |
Polynomial1< Real > & | operator-= (Polynomial1< Real > &p0, Polynomial1< Real > const &p1) |
template<typename Real > | |
Polynomial1< Real > & | operator-= (Polynomial1< Real > &p, Real scalar) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > & | operator-= (Matrix< NumRows, NumCols, Real > &M0, Matrix< NumRows, NumCols, Real > const &M1) |
template<typename Real > | |
DualQuaternion< Real > & | operator-= (DualQuaternion< Real > &d0, DualQuaternion< Real > const &d1) |
float | operator/ (IEEEBinary16 x, IEEEBinary16 y) |
float | operator/ (IEEEBinary16 x, float y) |
float | operator/ (float x, IEEEBinary16 y) |
template<typename Real > | |
GVector< Real > | operator/ (GVector< Real > const &v, Real scalar) |
template<int N, typename Real > | |
Vector< N, Real > | operator/ (Vector< N, Real > const &v, Real scalar) |
template<typename Real > | |
GMatrix< Real > | operator/ (GMatrix< Real > const &M, Real scalar) |
template<int N, typename Real > | |
Vector< N, Real > | operator/ (Vector< N, Real > const &v0, Vector< N, Real > const &v1) |
template<typename Real > | |
Polynomial1< Real > | operator/ (Polynomial1< Real > const &p, Real scalar) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | operator/ (Matrix< NumRows, NumCols, Real > const &M, Real scalar) |
template<typename Real > | |
DualQuaternion< Real > | operator/ (DualQuaternion< Real > const &d, Real scalar) |
IEEEBinary16 & | operator/= (IEEEBinary16 &x, IEEEBinary16 y) |
IEEEBinary16 & | operator/= (IEEEBinary16 &x, float y) |
template<typename Real > | |
GVector< Real > & | operator/= (GVector< Real > &v, Real scalar) |
template<int N, typename Real > | |
Vector< N, Real > & | operator/= (Vector< N, Real > &v, Real scalar) |
template<int N, typename Real > | |
Vector< N, Real > & | operator/= (Vector< N, Real > &v0, Vector< N, Real > const &v1) |
template<typename Real > | |
GMatrix< Real > & | operator/= (GMatrix< Real > &M, Real scalar) |
template<typename Real > | |
Polynomial1< Real > & | operator/= (Polynomial1< Real > &p, Real scalar) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > & | operator/= (Matrix< NumRows, NumCols, Real > &M, Real scalar) |
template<typename Real > | |
DualQuaternion< Real > & | operator/= (DualQuaternion< Real > &d, Real scalar) |
template<typename Real > | |
Real | Orthonormalize (int numElements, GVector< Real > *v, bool robust=false) |
template<int N, typename Real > | |
Real | Orthonormalize (int numElements, Vector< N, Real > *v, bool robust=false) |
template<typename Real > | |
GMatrix< Real > | OuterProduct (GVector< Real > const &U, GVector< Real > const &V) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumRows, NumCols, Real > | OuterProduct (Vector< NumRows, Real > const &U, Vector< NumCols, Real > const &V) |
static void | Permute (int u0, int u1, int u2, int V[4]) |
template<typename Real > | |
Vector2< Real > | Perp (Vector2< Real > const &v) |
template<typename Real > | |
void | Project (Ellipse2< Real > const &ellipse, Line2< Real > const &line, Real &smin, Real &smax) |
template<typename Real > | |
void | Project (Ellipsoid3< Real > const &ellipsoid, Line3< Real > const &line, Real &smin, Real &smax) |
template<typename Real > | |
GVector< Real > | Project (GVector< Real > const &v, int reject) |
template<int N, typename Real > | |
Vector< N-1, Real > | Project (Vector< N, Real > const &v, int reject) |
template<typename Iterable , typename Iterator = decltype(std::begin(std::declval<Iterable>())), typename ReverseIterator = std::reverse_iterator<Iterator>> | |
ReversalObject< ReverseIterator > | reverse (Iterable &&range) |
template<typename Real > | |
Vector< 4, Real > | RigidTransform (DualQuaternion< Real > const &d, Vector< 4, Real > const &v) |
template<typename Real > | |
Vector< 4, Real > | Rotate (Quaternion< Real > const &q, Vector< 4, Real > const &v) |
GTE_IMPEXP uint32_t | RoundDownToPowerOfTwo (uint32_t value) |
GTE_IMPEXP uint64_t | RoundUpToPowerOfTwo (uint32_t value) |
template<typename T > | |
ULONG | SafeRelease (T *&object) |
HRESULT | SetPrivateName (ID3D11DeviceChild *object, std::string const &name) |
HRESULT | SetPrivateName (IDXGIObject *object, std::string const &name) |
template<typename Real > | |
Quaternion< Real > | Slerp (Real t, Quaternion< Real > const &q0, Quaternion< Real > const &q1) |
template<typename Real > | |
Quaternion< Real > | SlerpR (Real t, Quaternion< Real > const &q0, Quaternion< Real > const &q1) |
template<typename Real > | |
Quaternion< Real > | SlerpRP (Real t, Quaternion< Real > const &q0, Quaternion< Real > const &q1, Real cosA) |
template<typename Real > | |
Real | Trace (Matrix3x3< Real > const &M) |
template<typename Real > | |
Real | Trace (Matrix4x4< Real > const &M) |
template<typename Real > | |
Real | Trace (Matrix2x2< Real > const &M) |
template<typename Real > | |
GMatrix< Real > | Transpose (GMatrix< Real > const &M) |
template<int NumRows, int NumCols, typename Real > | |
Matrix< NumCols, NumRows, Real > | Transpose (Matrix< NumRows, NumCols, Real > const &M) |
template<int N, typename Real > | |
Vector< N, Real > | UnitCross (Vector< N, Real > const &v0, Vector< N, Real > const &v1, bool robust=false) |
template<typename Real > | |
Vector4< Real > | UnitHyperCross (Vector4< Real > const &v0, Vector4< Real > const &v1, Vector4< Real > const &v2, bool robust=false) |
template<typename Real > | |
Vector2< Real > | UnitPerp (Vector2< Real > const &v, bool robust=false) |
Variables | |
GTE_IMPEXP int const | gMarchingCubesTable [256][41] |
static int32_t const | gsLeadingBitTable [32] |
static int32_t const | gsTrailingBitTable [32] |
GTE_IMPEXP WindowSystem | TheWindowSystem |
using gte::AlignedBox2 = typedef AlignedBox<2, Real> |
Definition at line 54 of file GteAlignedBox.h.
using gte::AlignedBox3 = typedef AlignedBox<3, Real> |
Definition at line 57 of file GteAlignedBox.h.
typedef std::vector<MemberLayout> gte::BufferLayout |
Definition at line 28 of file GteMemberLayout.h.
typedef std::function<void(std::shared_ptr<Buffer> const&)> gte::BufferUpdater |
Definition at line 24 of file GteBuffer.h.
using gte::Capsule3 = typedef Capsule<3, Real> |
Definition at line 44 of file GteCapsule.h.
using gte::Circle2 = typedef Hypersphere<2, Real> |
Definition at line 44 of file GteHypersphere.h.
using gte::Cone3 = typedef Cone<3, Real> |
using gte::DCPLine2Line2 = typedef DCPLineLine<2, Real> |
Definition at line 35 of file GteDistLineLine.h.
using gte::DCPLine2Ray2 = typedef DCPLineRay<2, Real> |
Definition at line 36 of file GteDistLineRay.h.
using gte::DCPLine2Segment2 = typedef DCPLineSegment<2, Real> |
Definition at line 39 of file GteDistLineSegment.h.
using gte::DCPLine3Line3 = typedef DCPLineLine<3, Real> |
Definition at line 38 of file GteDistLineLine.h.
using gte::DCPLine3Ray3 = typedef DCPLineRay<3, Real> |
Definition at line 39 of file GteDistLineRay.h.
using gte::DCPLine3Rectangle3 = typedef DCPQuery<Real, Line3<Real>, Rectangle3<Real>> |
Definition at line 36 of file GteDistLine3Rectangle3.h.
using gte::DCPLine3Segment3 = typedef DCPLineSegment<3, Real> |
Definition at line 42 of file GteDistLineSegment.h.
using gte::DCPLineLine = typedef DCPQuery<Real, Line<N, Real>, Line<N, Real>> |
Definition at line 32 of file GteDistLineLine.h.
using gte::DCPLineRay = typedef DCPQuery<Real, Line<N, Real>, Ray<N, Real>> |
Definition at line 33 of file GteDistLineRay.h.
using gte::DCPLineSegment = typedef DCPQuery<Real, Line<N, Real>, Segment<N, Real>> |
Definition at line 36 of file GteDistLineSegment.h.
using gte::DCPPoint2AlignedBox2 = typedef DCPPointAlignedBox<2, Real> |
Definition at line 43 of file GteDistPointAlignedBox.h.
using gte::DCPPoint2Ellipse2 = typedef DCPPointHyperellipsoid<2, Real> |
Definition at line 91 of file GteDistPointHyperellipsoid.h.
using gte::DCPPoint2Line2 = typedef DCPPointLine<2, Real> |
Definition at line 37 of file GteDistPointLine.h.
using gte::DCPPoint2OrientedBox2 = typedef DCPPointOrientedBox<2, Real> |
Definition at line 39 of file GteDistPointOrientedBox.h.
using gte::DCPPoint2Ray2 = typedef DCPPointRay<2, Real> |
Definition at line 36 of file GteDistPointRay.h.
using gte::DCPPoint2Segment2 = typedef DCPPointSegment<2, Real> |
Definition at line 37 of file GteDistPointSegment.h.
using gte::DCPPoint2Triangle2 = typedef DCPPointTriangle<2, Real> |
Definition at line 48 of file GteDistPointTriangle.h.
using gte::DCPPoint3AlignedBox3 = typedef DCPPointAlignedBox<3, Real> |
Definition at line 46 of file GteDistPointAlignedBox.h.
using gte::DCPPoint3Ellipsoid3 = typedef DCPPointHyperellipsoid<3, Real> |
Definition at line 94 of file GteDistPointHyperellipsoid.h.
using gte::DCPPoint3Line3 = typedef DCPPointLine<3, Real> |
Definition at line 40 of file GteDistPointLine.h.
using gte::DCPPoint3OrientedBox3 = typedef DCPPointOrientedBox<3, Real> |
Definition at line 42 of file GteDistPointOrientedBox.h.
using gte::DCPPoint3Ray3 = typedef DCPPointRay<3, Real> |
Definition at line 39 of file GteDistPointRay.h.
using gte::DCPPoint3Segment3 = typedef DCPPointSegment<3, Real> |
Definition at line 40 of file GteDistPointSegment.h.
using gte::DCPPoint3Triangle3 = typedef DCPPointTriangle<3, Real> |
Definition at line 51 of file GteDistPointTriangle.h.
using gte::DCPPointAlignedBox = typedef DCPQuery<Real, Vector<N, Real>, AlignedBox<N, Real>> |
Definition at line 40 of file GteDistPointAlignedBox.h.
using gte::DCPPointHyperellipsoid = typedef DCPQuery<Real, Vector<N, Real>, Hyperellipsoid<N, Real>> |
Definition at line 88 of file GteDistPointHyperellipsoid.h.
using gte::DCPPointLine = typedef DCPQuery<Real, Vector<N, Real>, Line<N, Real>> |
Definition at line 34 of file GteDistPointLine.h.
using gte::DCPPointOrientedBox = typedef DCPQuery<Real, Vector<N, Real>, AlignedBox<N, Real>> |
Definition at line 36 of file GteDistPointOrientedBox.h.
using gte::DCPPointRay = typedef DCPQuery<Real, Vector<N, Real>, Ray<N, Real>> |
Definition at line 33 of file GteDistPointRay.h.
using gte::DCPPointSegment = typedef DCPQuery<Real, Vector<N, Real>, Segment<N, Real>> |
Definition at line 34 of file GteDistPointSegment.h.
using gte::DCPPointTriangle = typedef DCPQuery<Real, Vector<N, Real>, Triangle<N, Real>> |
Definition at line 45 of file GteDistPointTriangle.h.
using gte::DCPRay2Ray2 = typedef DCPRayRay<2, Real> |
Definition at line 35 of file GteDistRayRay.h.
using gte::DCPRay2Segment2 = typedef DCPRaySegment<2, Real> |
Definition at line 39 of file GteDistRaySegment.h.
using gte::DCPRay3Ray3 = typedef DCPRayRay<3, Real> |
Definition at line 38 of file GteDistRayRay.h.
using gte::DCPRay3Segment3 = typedef DCPRaySegment<3, Real> |
Definition at line 42 of file GteDistRaySegment.h.
using gte::DCPRayRay = typedef DCPQuery<Real, Ray<N, Real>, Ray<N, Real>> |
Definition at line 32 of file GteDistRayRay.h.
using gte::DCPRaySegment = typedef DCPQuery<Real, Ray<N, Real>, Segment<N, Real>> |
Definition at line 36 of file GteDistRaySegment.h.
using gte::DCPSegment2Segment2 = typedef DCPSegmentSegment<2, Real> |
Definition at line 75 of file GteDistSegmentSegment.h.
using gte::DCPSegment3Segment3 = typedef DCPSegmentSegment<3, Real> |
Definition at line 78 of file GteDistSegmentSegment.h.
using gte::DCPSegmentSegment = typedef DCPQuery<Real, Segment<N, Real>, Segment<N, Real>> |
Definition at line 72 of file GteDistSegmentSegment.h.
using gte::Ellipse2 = typedef Hyperellipsoid<2, Real> |
Definition at line 102 of file GteHyperellipsoid.h.
using gte::Ellipsoid3 = typedef Hyperellipsoid<3, Real> |
Definition at line 105 of file GteHyperellipsoid.h.
using gte::FIEllipses2 = typedef FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>> |
Definition at line 209 of file GteIntrEllipse2Ellipse2.h.
using gte::FIIntervalInterval = typedef FIQuery<Real, std::array<Real, 2>, std::array<Real, 2>> |
Definition at line 100 of file GteIntrIntervals.h.
using gte::Halfspace3 = typedef Halfspace<3, Real> |
Definition at line 46 of file GteHalfspace.h.
typedef IEEEBinary<float, uint32_t, 32, 24> gte::IEEEBinary32 |
Definition at line 116 of file GteIEEEBinary.h.
typedef IEEEBinary<double, uint64_t, 64, 53> gte::IEEEBinary64 |
Definition at line 117 of file GteIEEEBinary.h.
using gte::Line2 = typedef Line<2, Real> |
using gte::Line3 = typedef Line<3, Real> |
using gte::Matrix2x2 = typedef Matrix<2, 2, Real> |
Definition at line 18 of file GteMatrix2x2.h.
using gte::Matrix3x3 = typedef Matrix<3, 3, Real> |
Definition at line 18 of file GteMatrix3x3.h.
using gte::Matrix4x4 = typedef Matrix<4, 4, Real> |
Definition at line 18 of file GteMatrix4x4.h.
using gte::OrientedBox2 = typedef OrientedBox<2, Real> |
Definition at line 57 of file GteOrientedBox.h.
using gte::OrientedBox3 = typedef OrientedBox<3, Real> |
Definition at line 60 of file GteOrientedBox.h.
using gte::Plane3 = typedef Hyperplane<3, Real> |
Definition at line 55 of file GteHyperplane.h.
using gte::Rectangle3 = typedef Rectangle<3, Real> |
Definition at line 54 of file GteRectangle.h.
using gte::Segment2 = typedef Segment<2, Real> |
Definition at line 60 of file GteSegment.h.
using gte::Segment3 = typedef Segment<3, Real> |
Definition at line 63 of file GteSegment.h.
using gte::Sphere3 = typedef Hypersphere<3, Real> |
Definition at line 47 of file GteHypersphere.h.
typedef std::function<void(std::shared_ptr<TextureArray> const&, unsigned int)> gte::TextureArrayLevelUpdater |
Definition at line 47 of file GteTextureArray.h.
typedef std::function<void(std::shared_ptr<TextureArray> const&)> gte::TextureArrayUpdater |
Definition at line 46 of file GteTextureArray.h.
typedef std::function<void(std::shared_ptr<Texture> const&, unsigned int)> gte::TextureLevelUpdater |
Definition at line 93 of file GteTexture.h.
typedef std::function<void(std::shared_ptr<Texture> const&)> gte::TextureUpdater |
Definition at line 92 of file GteTexture.h.
using gte::TIAlignedBox3Cone3 = typedef TIQuery<Real, AlignedBox<3, Real>, Cone<3, Real>> |
Definition at line 67 of file GteIntrAlignedBox3Cone3.h.
using gte::TIEllipses2 = typedef TIQuery<Real, Ellipse2<Real>, Ellipse2<Real>> |
Definition at line 206 of file GteIntrEllipse2Ellipse2.h.
using gte::TIIntervalInterval = typedef TIQuery<Real, std::array<Real, 2>, std::array<Real, 2>> |
Definition at line 96 of file GteIntrIntervals.h.
using gte::TIOrientedBox3Cone3 = typedef TIQuery<Real, OrientedBox<3, Real>, Cone<3, Real>> |
Definition at line 48 of file GteIntrOrientedBox3Cone3.h.
using gte::Triangle2 = typedef Triangle<2, Real> |
Definition at line 44 of file GteTriangle.h.
using gte::Triangle3 = typedef Triangle<3, Real> |
Definition at line 47 of file GteTriangle.h.
using gte::Vector2 = typedef Vector<2, Real> |
Definition at line 17 of file GteVector2.h.
using gte::Vector3 = typedef Vector<3, Real> |
Definition at line 17 of file GteVector3.h.
using gte::Vector4 = typedef Vector<4, Real> |
Definition at line 17 of file GteVector4.h.
typedef std::vector<Visual*> gte::VisibleSet |
Definition at line 47 of file GteCuller.h.
Enumerator | |
---|---|
SPLIT_BY_PLANE | |
POSITIVE_SIDE_VERTEX | |
POSITIVE_SIDE_EDGE | |
POSITIVE_SIDE_STRICT | |
NEGATIVE_SIDE_VERTEX | |
NEGATIVE_SIDE_EDGE | |
NEGATIVE_SIDE_STRICT | |
COINCIDENT_WITH_PLANE | |
INVALID_POLYGON |
Definition at line 98 of file GteIntrConvexPolygonPlane.h.
enum gte::EulerResult |
Enumerator | |
---|---|
ER_INVALID | |
ER_UNIQUE | |
ER_NOT_UNIQUE_SUM | |
ER_NOT_UNIQUE_DIF |
Definition at line 24 of file GteEulerAngles.h.
|
strong |
Definition at line 75 of file GteMatrix3x3.h.
Definition at line 142 of file GteMatrix4x4.h.
Definition at line 108 of file GteMatrix2x2.h.
bool gte::ApproximateEllipseByArcs | ( | Real | a, |
Real | b, | ||
int | numArcs, | ||
std::vector< Vector2< Real >> & | points, | ||
std::vector< Vector2< Real >> & | centers, | ||
std::vector< Real > & | radii | ||
) |
Definition at line 38 of file GteApprEllipseByArcs.h.
T gte::AtomicMax | ( | std::atomic< T > & | v0, |
T const & | v1 | ||
) |
Definition at line 40 of file GteAtomicMinMax.h.
T gte::AtomicMin | ( | std::atomic< T > & | v0, |
T const & | v1 | ||
) |
Definition at line 28 of file GteAtomicMinMax.h.
bool gte::Circumscribe | ( | Vector2< Real > const & | v0, |
Vector2< Real > const & | v1, | ||
Vector2< Real > const & | v2, | ||
Circle2< Real > & | circle | ||
) |
Definition at line 31 of file GteContScribeCircle2.h.
bool gte::Circumscribe | ( | Vector3< Real > const & | v0, |
Vector3< Real > const & | v1, | ||
Vector3< Real > const & | v2, | ||
Circle3< Real > & | circle | ||
) |
Definition at line 42 of file GteContScribeCircle3Sphere3.h.
bool gte::Circumscribe | ( | Vector3< Real > const & | v0, |
Vector3< Real > const & | v1, | ||
Vector3< Real > const & | v2, | ||
Vector3< Real > const & | v3, | ||
Sphere3< Real > & | sphere | ||
) |
Definition at line 66 of file GteContScribeCircle3Sphere3.h.
bool gte::ComputeBarycentrics | ( | Vector2< Real > const & | p, |
Vector2< Real > const & | v0, | ||
Vector2< Real > const & | v1, | ||
Vector2< Real > const & | v2, | ||
Real | bary[3], | ||
Real | epsilon = (Real)0 |
||
) |
Definition at line 135 of file GteVector2.h.
bool gte::ComputeBarycentrics | ( | Vector3< Real > const & | p, |
Vector3< Real > const & | v0, | ||
Vector3< Real > const & | v1, | ||
Vector3< Real > const & | v2, | ||
Vector3< Real > const & | v3, | ||
Real | bary[4], | ||
Real | epsilon = (Real)0 |
||
) |
Definition at line 174 of file GteVector3.h.
bool gte::ComputeExtremes | ( | int | numVectors, |
GVector< Real > const * | v, | ||
GVector< Real > & | vmin, | ||
GVector< Real > & | vmax | ||
) |
Definition at line 537 of file GteGVector.h.
bool gte::ComputeExtremes | ( | int | numVectors, |
Vector< N, Real > const * | v, | ||
Vector< N, Real > & | vmin, | ||
Vector< N, Real > & | vmax | ||
) |
Definition at line 609 of file GteVector.h.
void gte::ComputeMassProperties | ( | Vector3< Real > const * | vertices, |
int | numTriangles, | ||
int const * | indices, | ||
bool | bodyCoords, | ||
Real & | mass, | ||
Vector3< Real > & | center, | ||
Matrix3x3< Real > & | inertia | ||
) |
Definition at line 33 of file GtePolyhedralMassProperties.h.
Real gte::ComputeOrthogonalComplement | ( | int | numInputs, |
Vector2< Real > * | v, | ||
bool | robust = false |
||
) |
Definition at line 123 of file GteVector2.h.
Real gte::ComputeOrthogonalComplement | ( | int | numInputs, |
Vector3< Real > * | v, | ||
bool | robust = false |
||
) |
Definition at line 149 of file GteVector3.h.
Real gte::ComputeOrthogonalComplement | ( | int | numInputs, |
Vector4< Real > * | v, | ||
bool | robust = false |
||
) |
Definition at line 92 of file GteVector4.h.
Quaternion< Real > gte::Conjugate | ( | Quaternion< Real > const & | q | ) |
Definition at line 243 of file GteQuaternion.h.
DualQuaternion<Real> gte::Conjugate | ( | DualQuaternion< Real > const & | d | ) |
Vector< N, Real > gte::Cross | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 117 of file GteVector3.h.
DualQuaternion<Real> gte::Cross | ( | DualQuaternion< Real > const & | d0, |
DualQuaternion< Real > const & | d1 | ||
) |
Real gte::Determinant | ( | Matrix3x3< Real > const & | M | ) |
Definition at line 92 of file GteMatrix3x3.h.
Real gte::Determinant | ( | Matrix4x4< Real > const & | M | ) |
Definition at line 179 of file GteMatrix4x4.h.
Real gte::Determinant | ( | Matrix2x2< Real > const & | M | ) |
Definition at line 118 of file GteMatrix2x2.h.
Real gte::Determinant | ( | GMatrix< Real > const & | M | ) |
Definition at line 618 of file GteGMatrix.h.
Real gte::Determinant | ( | Matrix< N, N, Real > const & | M | ) |
Definition at line 674 of file GteMatrix.h.
Definition at line 400 of file GteGVector.h.
Real gte::Dot | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 454 of file GteVector.h.
DualQuaternion<Real> gte::Dot | ( | DualQuaternion< Real > const & | d0, |
DualQuaternion< Real > const & | d1 | ||
) |
Real gte::DotCross | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1, | ||
Vector< N, Real > const & | v2 | ||
) |
Definition at line 140 of file GteVector3.h.
Real gte::DotHyperCross | ( | Vector4< Real > const & | v0, |
Vector4< Real > const & | v1, | ||
Vector4< Real > const & | v2, | ||
Vector4< Real > const & | v3 | ||
) |
Definition at line 85 of file GteVector4.h.
Real gte::DotPerp | ( | Vector2< Real > const & | v0, |
Vector2< Real > const & | v1 | ||
) |
Definition at line 117 of file GteVector2.h.
|
inline |
Definition at line 42 of file GteDX11Include.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector2< Real > const * | points, | ||
Circle2< Real > & | circle | ||
) |
Definition at line 33 of file GteContCircle2.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector2< Real > const * | points, | ||
OrientedBox2< Real > & | box | ||
) |
Definition at line 37 of file GteContOrientedBox2.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector3< Real > const * | points, | ||
Sphere3< Real > & | sphere | ||
) |
Definition at line 33 of file GteContSphere3.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector3< Real > const * | points, | ||
Cylinder3< Real > & | cylinder | ||
) |
Definition at line 30 of file GteContCylinder3.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector3< Real > const * | points, | ||
OrientedBox3< Real > & | box | ||
) |
Definition at line 39 of file GteContOrientedBox3.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector3< Real > const * | points, | ||
Capsule3< Real > & | capsule | ||
) |
Definition at line 47 of file GteContCapsule3.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector2< Real > const * | points, | ||
Ellipse2< Real > & | ellipse | ||
) |
Definition at line 40 of file GteContEllipse2.h.
bool gte::GetContainer | ( | int | numPoints, |
Vector3< Real > const * | points, | ||
Ellipsoid3< Real > & | ellipsoid | ||
) |
Definition at line 43 of file GteContEllipsoid3.h.
int32_t gte::GetLeadingBit | ( | uint32_t | value | ) |
Definition at line 61 of file GteBitHacks.cpp.
int32_t gte::GetLeadingBit | ( | int32_t | value | ) |
Definition at line 72 of file GteBitHacks.cpp.
int32_t gte::GetLeadingBit | ( | uint64_t | value | ) |
Definition at line 83 of file GteBitHacks.cpp.
int32_t gte::GetLeadingBit | ( | int64_t | value | ) |
Definition at line 95 of file GteBitHacks.cpp.
Vector< N, Real > gte::GetOrthogonal | ( | Vector< N, Real > const & | v, |
bool | unitLength | ||
) |
Definition at line 574 of file GteVector.h.
Real gte::GetRotationAngle | ( | Matrix2x2< Real > const & | rotation | ) |
Definition at line 69 of file GteMatrix2x2.h.
int32_t gte::GetTrailingBit | ( | uint32_t | value | ) |
Definition at line 107 of file GteBitHacks.cpp.
int32_t gte::GetTrailingBit | ( | int32_t | value | ) |
Definition at line 116 of file GteBitHacks.cpp.
int32_t gte::GetTrailingBit | ( | uint64_t | value | ) |
Definition at line 122 of file GteBitHacks.cpp.
int32_t gte::GetTrailingBit | ( | int64_t | value | ) |
Definition at line 134 of file GteBitHacks.cpp.
Definition at line 574 of file GteGVector.h.
Vector< N+1, Real > gte::HLift | ( | Vector< N, Real > const & | v, |
Real | last | ||
) |
Definition at line 638 of file GteVector.h.
Matrix< N+1, N+1, Real > gte::HLift | ( | Matrix< N, N, Real > const & | M | ) |
Definition at line 888 of file GteMatrix.h.
Definition at line 587 of file GteGVector.h.
Definition at line 650 of file GteVector.h.
Matrix< N-1, N-1, Real > gte::HProject | ( | Matrix< N, N, Real > const & | M | ) |
Definition at line 904 of file GteMatrix.h.
Vector4< Real > gte::HyperCross | ( | Vector4< Real > const & | v0, |
Vector4< Real > const & | v1, | ||
Vector4< Real > const & | v2 | ||
) |
Definition at line 57 of file GteVector4.h.
bool gte::InContainer | ( | Vector2< Real > const & | point, |
Circle2< Real > const & | circle | ||
) |
Definition at line 58 of file GteContCircle2.h.
bool gte::InContainer | ( | Vector3< Real > const & | point, |
Sphere3< Real > const & | sphere | ||
) |
Definition at line 58 of file GteContSphere3.h.
bool gte::InContainer | ( | Vector3< Real > const & | point, |
Cylinder3< Real > const & | cylinder | ||
) |
Definition at line 74 of file GteContCylinder3.h.
bool gte::InContainer | ( | Vector2< Real > const & | point, |
OrientedBox2< Real > const & | box | ||
) |
Definition at line 84 of file GteContOrientedBox2.h.
bool gte::InContainer | ( | Vector3< Real > const & | point, |
OrientedBox3< Real > const & | box | ||
) |
Definition at line 88 of file GteContOrientedBox3.h.
bool gte::InContainer | ( | Vector3< Real > const & | point, |
Capsule3< Real > const & | capsule | ||
) |
Definition at line 114 of file GteContCapsule3.h.
bool gte::InContainer | ( | Vector2< Real > const & | point, |
Ellipse2< Real > const & | ellipse | ||
) |
Definition at line 105 of file GteContEllipse2.h.
bool gte::InContainer | ( | Sphere3< Real > const & | sphere, |
Capsule3< Real > const & | capsule | ||
) |
Definition at line 122 of file GteContCapsule3.h.
bool gte::InContainer | ( | Vector3< Real > const & | point, |
Ellipsoid3< Real > const & | ellipsoid | ||
) |
Definition at line 109 of file GteContEllipsoid3.h.
bool gte::InContainer | ( | Capsule3< Real > const & | testCapsule, |
Capsule3< Real > const & | capsule | ||
) |
Definition at line 135 of file GteContCapsule3.h.
bool gte::Inscribe | ( | Vector2< Real > const & | v0, |
Vector2< Real > const & | v1, | ||
Vector2< Real > const & | v2, | ||
Circle2< Real > & | circle | ||
) |
Definition at line 49 of file GteContScribeCircle2.h.
bool gte::Inscribe | ( | Vector3< Real > const & | v0, |
Vector3< Real > const & | v1, | ||
Vector3< Real > const & | v2, | ||
Circle3< Real > & | circle | ||
) |
Definition at line 94 of file GteContScribeCircle3Sphere3.h.
bool gte::Inscribe | ( | Vector3< Real > const & | v0, |
Vector3< Real > const & | v1, | ||
Vector3< Real > const & | v2, | ||
Vector3< Real > const & | v3, | ||
Sphere3< Real > & | sphere | ||
) |
Definition at line 139 of file GteContScribeCircle3Sphere3.h.
Matrix3x3< Real > gte::Inverse | ( | Matrix3x3< Real > const & | M, |
bool * | reportInvertibility = nullptr |
||
) |
Definition at line 36 of file GteMatrix3x3.h.
Matrix4x4< Real > gte::Inverse | ( | Matrix4x4< Real > const & | M, |
bool * | reportInvertibility = nullptr |
||
) |
Definition at line 87 of file GteMatrix4x4.h.
Matrix2x2< Real > gte::Inverse | ( | Matrix2x2< Real > const & | M, |
bool * | reportInvertibility = nullptr |
||
) |
Definition at line 79 of file GteMatrix2x2.h.
GMatrix< Real > gte::Inverse | ( | GMatrix< Real > const & | M, |
bool * | reportInvertibility = nullptr |
||
) |
Definition at line 590 of file GteGMatrix.h.
Matrix< N, N, Real > gte::Inverse | ( | Matrix< N, N, Real > const & | M, |
bool * | reportInvertibility = nullptr |
||
) |
Definition at line 659 of file GteMatrix.h.
Quaternion< Real > gte::Inverse | ( | Quaternion< Real > const & | d | ) |
Definition at line 227 of file GteQuaternion.h.
bool gte::IsPowerOfTwo | ( | uint32_t | value | ) |
Definition at line 31 of file GteBitHacks.cpp.
bool gte::IsPowerOfTwo | ( | int32_t | value | ) |
Definition at line 36 of file GteBitHacks.cpp.
Real gte::L1Norm | ( | GMatrix< Real > const & | M | ) |
Definition at line 553 of file GteGMatrix.h.
Real gte::L1Norm | ( | Matrix< NumRows, NumCols, Real > const & | M | ) |
Definition at line 622 of file GteMatrix.h.
Real gte::L2Norm | ( | GMatrix< Real > const & | M | ) |
Definition at line 564 of file GteGMatrix.h.
Real gte::L2Norm | ( | Matrix< NumRows, NumCols, Real > const & | M | ) |
Definition at line 633 of file GteMatrix.h.
Real gte::Length | ( | GVector< Real > const & | v, |
bool | robust = false |
||
) |
Definition at line 421 of file GteGVector.h.
Real gte::Length | ( | Vector< N, Real > const & | v, |
bool | robust = false |
||
) |
Definition at line 465 of file GteVector.h.
DualQuaternion<Real> gte::Length | ( | DualQuaternion< Real > const & | d, |
bool | robust = false |
||
) |
GVector< Real > gte::Lift | ( | GVector< Real > const & | v, |
int | inject, | ||
Real | value | ||
) |
Definition at line 606 of file GteGVector.h.
Vector< N+1, Real > gte::Lift | ( | Vector< N, Real > const & | v, |
int | inject, | ||
Real | value | ||
) |
Definition at line 662 of file GteVector.h.
Real gte::LInfinityNorm | ( | GMatrix< Real > const & | M | ) |
Definition at line 575 of file GteGMatrix.h.
Real gte::LInfinityNorm | ( | Matrix< NumRows, NumCols, Real > const & | M | ) |
Definition at line 644 of file GteMatrix.h.
uint32_t gte::Log2OfPowerOfTwo | ( | uint32_t | powerOfTwo | ) |
Definition at line 41 of file GteBitHacks.cpp.
int32_t gte::Log2OfPowerOfTwo | ( | int32_t | powerOfTwo | ) |
Definition at line 51 of file GteBitHacks.cpp.
Definition at line 829 of file GteGMatrix.h.
void gte::MakeDiagonal | ( | Vector< N, Real > const & | D, |
Matrix< N, N, Real > & | M | ||
) |
Definition at line 874 of file GteMatrix.h.
Matrix4x4< Real > gte::MakeObliqueProjection | ( | Vector4< Real > const & | origin, |
Vector4< Real > const & | normal, | ||
Vector4< Real > const & | direction | ||
) |
Definition at line 205 of file GteMatrix4x4.h.
Matrix4x4< Real > gte::MakePerspectiveProjection | ( | Vector4< Real > const & | origin, |
Vector4< Real > const & | normal, | ||
Vector4< Real > const & | eye | ||
) |
Definition at line 254 of file GteMatrix4x4.h.
Matrix4x4< Real > gte::MakeReflection | ( | Vector4< Real > const & | origin, |
Vector4< Real > const & | normal | ||
) |
Definition at line 301 of file GteMatrix4x4.h.
Definition at line 51 of file GteMatrix2x2.h.
Definition at line 16 of file GteWrapper.cpp.
void gte::Memcpy | ( | wchar_t * | target, |
wchar_t const * | source, | ||
size_t | count | ||
) |
Definition at line 26 of file GteWrapper.cpp.
bool gte::MergeContainers | ( | Circle2< Real > const & | circle0, |
Circle2< Real > const & | circle1, | ||
Circle2< Real > & | merge | ||
) |
Definition at line 65 of file GteContCircle2.h.
bool gte::MergeContainers | ( | Sphere3< Real > const & | sphere0, |
Sphere3< Real > const & | sphere1, | ||
Sphere3< Real > & | merge | ||
) |
Definition at line 65 of file GteContSphere3.h.
bool gte::MergeContainers | ( | OrientedBox2< Real > const & | box0, |
OrientedBox2< Real > const & | box1, | ||
OrientedBox2< Real > & | merge | ||
) |
Definition at line 99 of file GteContOrientedBox2.h.
bool gte::MergeContainers | ( | OrientedBox3< Real > const & | box0, |
OrientedBox3< Real > const & | box1, | ||
OrientedBox3< Real > & | merge | ||
) |
Definition at line 103 of file GteContOrientedBox3.h.
bool gte::MergeContainers | ( | Ellipse2< Real > const & | ellipse0, |
Ellipse2< Real > const & | ellipse1, | ||
Ellipse2< Real > & | merge | ||
) |
Definition at line 115 of file GteContEllipse2.h.
bool gte::MergeContainers | ( | Ellipsoid3< Real > const & | ellipsoid0, |
Ellipsoid3< Real > const & | ellipsoid1, | ||
Ellipsoid3< Real > & | merge | ||
) |
Definition at line 121 of file GteContEllipsoid3.h.
bool gte::MergeContainers | ( | Capsule3< Real > const & | capsule0, |
Capsule3< Real > const & | capsule1, | ||
Capsule3< Real > & | merge | ||
) |
Definition at line 145 of file GteContCapsule3.h.
GMatrix< Real > gte::MultiplyAB | ( | GMatrix< Real > const & | A, |
GMatrix< Real > const & | B | ||
) |
Definition at line 693 of file GteGMatrix.h.
Matrix< NumRows, NumCols, Real > gte::MultiplyAB | ( | Matrix< NumRows, NumCommon, Real > const & | A, |
Matrix< NumCommon, NumCols, Real > const & | B | ||
) |
Definition at line 742 of file GteMatrix.h.
GMatrix< Real > gte::MultiplyABT | ( | GMatrix< Real > const & | A, |
GMatrix< Real > const & | B | ||
) |
Definition at line 715 of file GteGMatrix.h.
Matrix< NumRows, NumCols, Real > gte::MultiplyABT | ( | Matrix< NumRows, NumCommon, Real > const & | A, |
Matrix< NumCols, NumCommon, Real > const & | B | ||
) |
Definition at line 763 of file GteMatrix.h.
GMatrix< Real > gte::MultiplyATB | ( | GMatrix< Real > const & | A, |
GMatrix< Real > const & | B | ||
) |
Definition at line 737 of file GteGMatrix.h.
Matrix< NumRows, NumCols, Real > gte::MultiplyATB | ( | Matrix< NumCommon, NumRows, Real > const & | A, |
Matrix< NumCommon, NumCols, Real > const & | B | ||
) |
Definition at line 784 of file GteMatrix.h.
GMatrix< Real > gte::MultiplyATBT | ( | GMatrix< Real > const & | A, |
GMatrix< Real > const & | B | ||
) |
Definition at line 759 of file GteGMatrix.h.
Matrix< NumRows, NumCols, Real > gte::MultiplyATBT | ( | Matrix< NumCommon, NumRows, Real > const & | A, |
Matrix< NumCols, NumCommon, Real > const & | B | ||
) |
Definition at line 805 of file GteMatrix.h.
GMatrix< Real > gte::MultiplyDM | ( | GVector< Real > const & | D, |
GMatrix< Real > const & | M | ||
) |
Definition at line 798 of file GteGMatrix.h.
Matrix< NumRows, NumCols, Real > gte::MultiplyDM | ( | Vector< NumRows, Real > const & | D, |
Matrix< NumRows, NumCols, Real > const & | M | ||
) |
Definition at line 843 of file GteMatrix.h.
GMatrix< Real > gte::MultiplyMD | ( | GMatrix< Real > const & | M, |
GVector< Real > const & | D | ||
) |
Definition at line 781 of file GteGMatrix.h.
Matrix< NumRows, NumCols, Real > gte::MultiplyMD | ( | Matrix< NumRows, NumCols, Real > const & | M, |
Vector< NumCols, Real > const & | D | ||
) |
Definition at line 826 of file GteMatrix.h.
DualQuaternion<Real> gte::Norm | ( | DualQuaternion< Real > & | d, |
bool | robust = false |
||
) |
Real gte::Normalize | ( | GVector< Real > & | v, |
bool | robust = false |
||
) |
Definition at line 454 of file GteGVector.h.
Real gte::Normalize | ( | Vector< N, Real > & | v, |
bool | robust = false |
||
) |
Definition at line 498 of file GteVector.h.
Quaternion< Real > gte::operator* | ( | Quaternion< Real > const & | q0, |
Quaternion< Real > const & | q1 | ||
) |
Definition at line 207 of file GteQuaternion.h.
float gte::operator* | ( | IEEEBinary16 | x, |
IEEEBinary16 | y | ||
) |
Definition at line 270 of file GteIEEEBinary16.cpp.
float gte::operator* | ( | IEEEBinary16 | x, |
float | y | ||
) |
Definition at line 290 of file GteIEEEBinary16.cpp.
float gte::operator* | ( | float | x, |
IEEEBinary16 | y | ||
) |
Definition at line 310 of file GteIEEEBinary16.cpp.
Definition at line 310 of file GteGVector.h.
Definition at line 317 of file GteGVector.h.
Vector< N, Real > gte::operator* | ( | Vector< N, Real > const & | v, |
Real | scalar | ||
) |
Definition at line 346 of file GteVector.h.
Vector< N, Real > gte::operator* | ( | Real | scalar, |
Vector< N, Real > const & | v | ||
) |
Definition at line 353 of file GteVector.h.
Polynomial1< Real > gte::operator* | ( | Polynomial1< Real > const & | p0, |
Polynomial1< Real > const & | p1 | ||
) |
Definition at line 450 of file GtePolynomial1.h.
Definition at line 471 of file GteGMatrix.h.
Definition at line 478 of file GteGMatrix.h.
Vector< N, Real > gte::operator* | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 418 of file GteVector.h.
Polynomial1< Real > gte::operator* | ( | Polynomial1< Real > const & | p, |
Real | scalar | ||
) |
Definition at line 519 of file GtePolynomial1.h.
Polynomial1< Real > gte::operator* | ( | Real | scalar, |
Polynomial1< Real > const & | p | ||
) |
Definition at line 531 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > gte::operator* | ( | Matrix< NumRows, NumCols, Real > const & | M, |
Real | scalar | ||
) |
Definition at line 540 of file GteMatrix.h.
Matrix< NumRows, NumCols, Real > gte::operator* | ( | Real | scalar, |
Matrix< NumRows, NumCols, Real > const & | M | ||
) |
Definition at line 548 of file GteMatrix.h.
GVector< Real > gte::operator* | ( | GMatrix< Real > const & | M, |
GVector< Real > const & | V | ||
) |
Definition at line 651 of file GteGMatrix.h.
GVector< Real > gte::operator* | ( | GVector< Real > const & | V, |
GMatrix< Real > const & | M | ||
) |
Definition at line 669 of file GteGMatrix.h.
GMatrix< Real > gte::operator* | ( | GMatrix< Real > const & | A, |
GMatrix< Real > const & | B | ||
) |
Definition at line 687 of file GteGMatrix.h.
Definition at line 487 of file GteTransform.cpp.
Definition at line 492 of file GteTransform.cpp.
Definition at line 497 of file GteTransform.cpp.
Vector< NumRows, Real > gte::operator* | ( | Matrix< NumRows, NumCols, Real > const & | M, |
Vector< NumCols, Real > const & | V | ||
) |
Definition at line 699 of file GteMatrix.h.
Definition at line 267 of file GteTransform.h.
Definition at line 273 of file GteTransform.h.
Vector< NumCols, Real > gte::operator* | ( | Vector< NumRows, Real > const & | V, |
Matrix< NumRows, NumCols, Real > const & | M | ||
) |
Definition at line 716 of file GteMatrix.h.
Matrix< NumRows, NumCols, Real > gte::operator* | ( | Matrix< NumRows, NumCommon, Real > const & | A, |
Matrix< NumCommon, NumCols, Real > const & | B | ||
) |
Definition at line 733 of file GteMatrix.h.
DualQuaternion<Real> gte::operator* | ( | DualQuaternion< Real > const & | d, |
Real | scalar | ||
) |
DualQuaternion<Real> gte::operator* | ( | Real | scalar, |
DualQuaternion< Real > const & | d | ||
) |
DualQuaternion<Real> gte::operator* | ( | DualQuaternion< Real > const & | d0, |
DualQuaternion< Real > const & | d1 | ||
) |
IEEEBinary16 & gte::operator*= | ( | IEEEBinary16 & | x, |
IEEEBinary16 | y | ||
) |
Definition at line 332 of file GteIEEEBinary16.cpp.
IEEEBinary16 & gte::operator*= | ( | IEEEBinary16 & | x, |
float | y | ||
) |
Definition at line 356 of file GteIEEEBinary16.cpp.
Definition at line 369 of file GteGVector.h.
Vector< N, Real > & gte::operator*= | ( | Vector< N, Real > & | v, |
Real | scalar | ||
) |
Definition at line 387 of file GteVector.h.
Vector< N, Real > & gte::operator*= | ( | Vector< N, Real > & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 434 of file GteVector.h.
Definition at line 522 of file GteGMatrix.h.
Polynomial1< Real > & gte::operator*= | ( | Polynomial1< Real > & | p0, |
Polynomial1< Real > const & | p1 | ||
) |
Definition at line 577 of file GtePolynomial1.h.
Polynomial1< Real > & gte::operator*= | ( | Polynomial1< Real > & | p, |
Real | scalar | ||
) |
Definition at line 599 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > & gte::operator*= | ( | Matrix< NumRows, NumCols, Real > & | M, |
Real | scalar | ||
) |
Definition at line 590 of file GteMatrix.h.
DualQuaternion<Real>& gte::operator*= | ( | DualQuaternion< Real > & | d, |
Real | scalar | ||
) |
Definition at line 279 of file GteGVector.h.
Definition at line 313 of file GteVector.h.
float gte::operator+ | ( | IEEEBinary16 | x, |
IEEEBinary16 | y | ||
) |
Definition at line 260 of file GteIEEEBinary16.cpp.
float gte::operator+ | ( | IEEEBinary16 | x, |
float | y | ||
) |
Definition at line 280 of file GteIEEEBinary16.cpp.
GVector< Real > gte::operator+ | ( | GVector< Real > const & | v0, |
GVector< Real > const & | v1 | ||
) |
Definition at line 296 of file GteGVector.h.
Vector< N, Real > gte::operator+ | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 330 of file GteVector.h.
float gte::operator+ | ( | float | x, |
IEEEBinary16 | y | ||
) |
Definition at line 300 of file GteIEEEBinary16.cpp.
Polynomial1< Real > gte::operator+ | ( | Polynomial1< Real > const & | p | ) |
Definition at line 360 of file GtePolynomial1.h.
Definition at line 440 of file GteGMatrix.h.
Polynomial1< Real > gte::operator+ | ( | Polynomial1< Real > const & | p0, |
Polynomial1< Real > const & | p1 | ||
) |
Definition at line 378 of file GtePolynomial1.h.
GMatrix< Real > gte::operator+ | ( | GMatrix< Real > const & | M0, |
GMatrix< Real > const & | M1 | ||
) |
Definition at line 457 of file GteGMatrix.h.
Polynomial1< Real > gte::operator+ | ( | Polynomial1< Real > const & | p, |
Real | scalar | ||
) |
Definition at line 467 of file GtePolynomial1.h.
Polynomial1< Real > gte::operator+ | ( | Real | scalar, |
Polynomial1< Real > const & | p | ||
) |
Definition at line 480 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > gte::operator+ | ( | Matrix< NumRows, NumCols, Real > const & | M | ) |
Definition at line 501 of file GteMatrix.h.
Matrix< NumRows, NumCols, Real > gte::operator+ | ( | Matrix< NumRows, NumCols, Real > const & | M0, |
Matrix< NumRows, NumCols, Real > const & | M1 | ||
) |
Definition at line 520 of file GteMatrix.h.
DualQuaternion<Real> gte::operator+ | ( | DualQuaternion< Real > const & | d | ) |
DualQuaternion<Real> gte::operator+ | ( | DualQuaternion< Real > const & | d0, |
DualQuaternion< Real > const & | d1 | ||
) |
IEEEBinary16 & gte::operator+= | ( | IEEEBinary16 & | x, |
IEEEBinary16 | y | ||
) |
Definition at line 320 of file GteIEEEBinary16.cpp.
IEEEBinary16 & gte::operator+= | ( | IEEEBinary16 & | x, |
float | y | ||
) |
Definition at line 344 of file GteIEEEBinary16.cpp.
GVector< Real > & gte::operator+= | ( | GVector< Real > & | v0, |
GVector< Real > const & | v1 | ||
) |
Definition at line 331 of file GteGVector.h.
Vector< N, Real > & gte::operator+= | ( | Vector< N, Real > & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 367 of file GteVector.h.
GMatrix< Real > & gte::operator+= | ( | GMatrix< Real > & | M0, |
GMatrix< Real > const & | M1 | ||
) |
Definition at line 492 of file GteGMatrix.h.
Polynomial1< Real > & gte::operator+= | ( | Polynomial1< Real > & | p0, |
Polynomial1< Real > const & | p1 | ||
) |
Definition at line 561 of file GtePolynomial1.h.
Polynomial1< Real > & gte::operator+= | ( | Polynomial1< Real > & | p, |
Real | scalar | ||
) |
Definition at line 585 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > & gte::operator+= | ( | Matrix< NumRows, NumCols, Real > & | M0, |
Matrix< NumRows, NumCols, Real > const & | M1 | ||
) |
Definition at line 564 of file GteMatrix.h.
DualQuaternion<Real>& gte::operator+= | ( | DualQuaternion< Real > & | d0, |
DualQuaternion< Real > const & | d1 | ||
) |
IEEEBinary16 gte::operator- | ( | IEEEBinary16 | x | ) |
Definition at line 254 of file GteIEEEBinary16.cpp.
float gte::operator- | ( | IEEEBinary16 | x, |
IEEEBinary16 | y | ||
) |
Definition at line 265 of file GteIEEEBinary16.cpp.
Definition at line 285 of file GteGVector.h.
Definition at line 319 of file GteVector.h.
float gte::operator- | ( | IEEEBinary16 | x, |
float | y | ||
) |
Definition at line 285 of file GteIEEEBinary16.cpp.
GVector< Real > gte::operator- | ( | GVector< Real > const & | v0, |
GVector< Real > const & | v1 | ||
) |
Definition at line 303 of file GteGVector.h.
float gte::operator- | ( | float | x, |
IEEEBinary16 | y | ||
) |
Definition at line 305 of file GteIEEEBinary16.cpp.
Vector< N, Real > gte::operator- | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 338 of file GteVector.h.
Polynomial1< Real > gte::operator- | ( | Polynomial1< Real > const & | p | ) |
Definition at line 366 of file GtePolynomial1.h.
Definition at line 446 of file GteGMatrix.h.
Polynomial1< Real > gte::operator- | ( | Polynomial1< Real > const & | p0, |
Polynomial1< Real > const & | p1 | ||
) |
Definition at line 414 of file GtePolynomial1.h.
GMatrix< Real > gte::operator- | ( | GMatrix< Real > const & | M0, |
GMatrix< Real > const & | M1 | ||
) |
Definition at line 464 of file GteGMatrix.h.
Polynomial1< Real > gte::operator- | ( | Polynomial1< Real > const & | p, |
Real | scalar | ||
) |
Definition at line 493 of file GtePolynomial1.h.
Polynomial1< Real > gte::operator- | ( | Real | scalar, |
Polynomial1< Real > const & | p | ||
) |
Definition at line 506 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > gte::operator- | ( | Matrix< NumRows, NumCols, Real > const & | M | ) |
Definition at line 508 of file GteMatrix.h.
Matrix< NumRows, NumCols, Real > gte::operator- | ( | Matrix< NumRows, NumCols, Real > const & | M0, |
Matrix< NumRows, NumCols, Real > const & | M1 | ||
) |
Definition at line 530 of file GteMatrix.h.
DualQuaternion<Real> gte::operator- | ( | DualQuaternion< Real > const & | d | ) |
DualQuaternion<Real> gte::operator- | ( | DualQuaternion< Real > const & | d0, |
DualQuaternion< Real > const & | d1 | ||
) |
IEEEBinary16 & gte::operator-= | ( | IEEEBinary16 & | x, |
IEEEBinary16 | y | ||
) |
Definition at line 326 of file GteIEEEBinary16.cpp.
IEEEBinary16 & gte::operator-= | ( | IEEEBinary16 & | x, |
float | y | ||
) |
Definition at line 350 of file GteIEEEBinary16.cpp.
GVector< Real > & gte::operator-= | ( | GVector< Real > & | v0, |
GVector< Real > const & | v1 | ||
) |
Definition at line 350 of file GteGVector.h.
Vector< N, Real > & gte::operator-= | ( | Vector< N, Real > & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 377 of file GteVector.h.
GMatrix< Real > & gte::operator-= | ( | GMatrix< Real > & | M0, |
GMatrix< Real > const & | M1 | ||
) |
Definition at line 507 of file GteGMatrix.h.
Polynomial1< Real > & gte::operator-= | ( | Polynomial1< Real > & | p0, |
Polynomial1< Real > const & | p1 | ||
) |
Definition at line 569 of file GtePolynomial1.h.
Polynomial1< Real > & gte::operator-= | ( | Polynomial1< Real > & | p, |
Real | scalar | ||
) |
Definition at line 592 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > & gte::operator-= | ( | Matrix< NumRows, NumCols, Real > & | M0, |
Matrix< NumRows, NumCols, Real > const & | M1 | ||
) |
Definition at line 577 of file GteMatrix.h.
DualQuaternion<Real>& gte::operator-= | ( | DualQuaternion< Real > & | d0, |
DualQuaternion< Real > const & | d1 | ||
) |
float gte::operator/ | ( | IEEEBinary16 | x, |
IEEEBinary16 | y | ||
) |
Definition at line 275 of file GteIEEEBinary16.cpp.
float gte::operator/ | ( | IEEEBinary16 | x, |
float | y | ||
) |
Definition at line 295 of file GteIEEEBinary16.cpp.
float gte::operator/ | ( | float | x, |
IEEEBinary16 | y | ||
) |
Definition at line 315 of file GteIEEEBinary16.cpp.
Definition at line 324 of file GteGVector.h.
Vector< N, Real > gte::operator/ | ( | Vector< N, Real > const & | v, |
Real | scalar | ||
) |
Definition at line 360 of file GteVector.h.
Definition at line 485 of file GteGMatrix.h.
Vector< N, Real > gte::operator/ | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 426 of file GteVector.h.
Polynomial1< Real > gte::operator/ | ( | Polynomial1< Real > const & | p, |
Real | scalar | ||
) |
Definition at line 543 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > gte::operator/ | ( | Matrix< NumRows, NumCols, Real > const & | M, |
Real | scalar | ||
) |
Definition at line 556 of file GteMatrix.h.
DualQuaternion<Real> gte::operator/ | ( | DualQuaternion< Real > const & | d, |
Real | scalar | ||
) |
IEEEBinary16 & gte::operator/= | ( | IEEEBinary16 & | x, |
IEEEBinary16 | y | ||
) |
Definition at line 338 of file GteIEEEBinary16.cpp.
IEEEBinary16 & gte::operator/= | ( | IEEEBinary16 & | x, |
float | y | ||
) |
Definition at line 362 of file GteIEEEBinary16.cpp.
Definition at line 379 of file GteGVector.h.
Vector< N, Real > & gte::operator/= | ( | Vector< N, Real > & | v, |
Real | scalar | ||
) |
Definition at line 397 of file GteVector.h.
Vector< N, Real > & gte::operator/= | ( | Vector< N, Real > & | v0, |
Vector< N, Real > const & | v1 | ||
) |
Definition at line 444 of file GteVector.h.
Definition at line 532 of file GteGMatrix.h.
Polynomial1< Real > & gte::operator/= | ( | Polynomial1< Real > & | p, |
Real | scalar | ||
) |
Definition at line 606 of file GtePolynomial1.h.
Matrix< NumRows, NumCols, Real > & gte::operator/= | ( | Matrix< NumRows, NumCols, Real > & | M, |
Real | scalar | ||
) |
Definition at line 601 of file GteMatrix.h.
DualQuaternion<Real>& gte::operator/= | ( | DualQuaternion< Real > & | d, |
Real | scalar | ||
) |
Real gte::Orthonormalize | ( | int | numElements, |
GVector< Real > * | v, | ||
bool | robust = false |
||
) |
Definition at line 505 of file GteGVector.h.
Real gte::Orthonormalize | ( | int | numElements, |
Vector< N, Real > * | v, | ||
bool | robust = false |
||
) |
Definition at line 549 of file GteVector.h.
GMatrix< Real > gte::OuterProduct | ( | GVector< Real > const & | U, |
GVector< Real > const & | V | ||
) |
Definition at line 815 of file GteGMatrix.h.
Matrix< NumRows, NumCols, Real > gte::OuterProduct | ( | Vector< NumRows, Real > const & | U, |
Vector< NumCols, Real > const & | V | ||
) |
Definition at line 860 of file GteMatrix.h.
Definition at line 21 of file GteTetrahedronKey.cpp.
Definition at line 103 of file GteVector2.h.
void gte::Project | ( | Ellipse2< Real > const & | ellipse, |
Line2< Real > const & | line, | ||
Real & | smin, | ||
Real & | smax | ||
) |
Definition at line 30 of file GteProjection.h.
void gte::Project | ( | Ellipsoid3< Real > const & | ellipsoid, |
Line3< Real > const & | line, | ||
Real & | smin, | ||
Real & | smax | ||
) |
Definition at line 50 of file GteProjection.h.
Definition at line 625 of file GteGVector.h.
Vector< N-1, Real > gte::Project | ( | Vector< N, Real > const & | v, |
int | reject | ||
) |
Definition at line 680 of file GteVector.h.
ReversalObject<ReverseIterator> gte::reverse | ( | Iterable && | range | ) |
Definition at line 62 of file GteRangeIteration.h.
Vector<4, Real> gte::RigidTransform | ( | DualQuaternion< Real > const & | d, |
Vector< 4, Real > const & | v | ||
) |
Vector< 4, Real > gte::Rotate | ( | Quaternion< Real > const & | q, |
Vector< 4, Real > const & | v | ||
) |
Definition at line 249 of file GteQuaternion.h.
uint32_t gte::RoundDownToPowerOfTwo | ( | uint32_t | value | ) |
Definition at line 170 of file GteBitHacks.cpp.
uint64_t gte::RoundUpToPowerOfTwo | ( | uint32_t | value | ) |
Definition at line 146 of file GteBitHacks.cpp.
|
inline |
Definition at line 30 of file GteDX11Include.h.
|
inline |
Definition at line 78 of file GteDX11Include.h.
|
inline |
Definition at line 96 of file GteDX11Include.h.
Quaternion< Real > gte::Slerp | ( | Real | t, |
Quaternion< Real > const & | q0, | ||
Quaternion< Real > const & | q1 | ||
) |
Definition at line 259 of file GteQuaternion.h.
Quaternion< Real > gte::SlerpR | ( | Real | t, |
Quaternion< Real > const & | q0, | ||
Quaternion< Real > const & | q1 | ||
) |
Definition at line 280 of file GteQuaternion.h.
Quaternion< Real > gte::SlerpRP | ( | Real | t, |
Quaternion< Real > const & | q0, | ||
Quaternion< Real > const & | q1, | ||
Real | cosA | ||
) |
Definition at line 289 of file GteQuaternion.h.
Real gte::Trace | ( | Matrix3x3< Real > const & | M | ) |
Definition at line 102 of file GteMatrix3x3.h.
Real gte::Trace | ( | Matrix4x4< Real > const & | M | ) |
Definition at line 198 of file GteMatrix4x4.h.
Real gte::Trace | ( | Matrix2x2< Real > const & | M | ) |
Definition at line 125 of file GteMatrix2x2.h.
Definition at line 637 of file GteGMatrix.h.
Matrix< NumCols, NumRows, Real > gte::Transpose | ( | Matrix< NumRows, NumCols, Real > const & | M | ) |
Definition at line 684 of file GteMatrix.h.
Vector< N, Real > gte::UnitCross | ( | Vector< N, Real > const & | v0, |
Vector< N, Real > const & | v1, | ||
bool | robust = false |
||
) |
Definition at line 130 of file GteVector3.h.
Vector4< Real > gte::UnitHyperCross | ( | Vector4< Real > const & | v0, |
Vector4< Real > const & | v1, | ||
Vector4< Real > const & | v2, | ||
bool | robust = false |
||
) |
Definition at line 76 of file GteVector4.h.
Vector2< Real > gte::UnitPerp | ( | Vector2< Real > const & | v, |
bool | robust = false |
||
) |
Definition at line 109 of file GteVector2.h.
int const gte::gMarchingCubesTable |
Definition at line 13 of file GteMarchingCubesTable.cpp.
|
static |
Definition at line 14 of file GteBitHacks.cpp.
|
static |
Definition at line 22 of file GteBitHacks.cpp.
WindowSystem gte::TheWindowSystem |
Definition at line 26 of file MSW/DX11/GteWindowSystem.h.