This commit is contained in:
2025-11-28 23:13:44 +05:30
commit a3a8e79709
7360 changed files with 1156074 additions and 0 deletions

View File

@ -0,0 +1,209 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of NVIDIA CORPORATION nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ``AS IS'' AND ANY
// EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
// CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
// EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
// OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// Copyright (c) 2018 NVIDIA Corporation. All rights reserved.
#ifndef BOUNDS3_H
#define BOUNDS3_H
#include "Vec3.h"
// Singe / VecVecReal Precision Vec 3
// Matthias Mueller
// derived from Vec3.h
namespace M
{
class Bounds3
{
public:
Vec3 minimum, maximum;
Bounds3()
{
// Default to empty boxes for compatibility TODO: PT: remove this if useless
setEmpty();
}
~Bounds3()
{
//nothing
}
void setEmpty()
{
// We know use this particular pattern for empty boxes
set(MAX_VEC_REAL, MAX_VEC_REAL, MAX_VEC_REAL,
MIN_VEC_REAL, MIN_VEC_REAL, MIN_VEC_REAL);
}
void setInfinite()
{
set(MIN_VEC_REAL, MIN_VEC_REAL, MIN_VEC_REAL,
MAX_VEC_REAL, MAX_VEC_REAL, MAX_VEC_REAL);
}
void set(VecReal mi, VecReal miny, VecReal minz, VecReal maxx, VecReal maxy,VecReal maxz)
{
minimum.set(mi, miny, minz);
maximum.set(maxx, maxy, maxz);
}
void set(const Vec3& _min, const Vec3& _max)
{
minimum = _min;
maximum = _max;
}
void include(const Vec3& v)
{
maximum.max(v);
minimum.min(v);
}
void combine(const Bounds3& b2)
{
// - if we're empty, min = MAX,MAX,MAX => min will be b2 in all cases => it will copy b2, ok
// - if b2 is empty, the opposite happens => keep us unchanged => ok
// => same behavior as before, automatically
minimum.min(b2.minimum);
maximum.max(b2.maximum);
}
//void boundsOfOBB(const Mat33& orientation, const Vec3& translation, const Vec3& halfDims)
//{
//VecReal dimx = halfDims[0];
//VecReal dimy = halfDims[1];
//VecReal dimz = halfDims[2];
//VecReal x = Math::abs(orientation(0,0) * dimx) + Math::abs(orientation(0,1) * dimy) + Math::abs(orientation(0,2) * dimz);
//VecReal y = Math::abs(orientation(1,0) * dimx) + Math::abs(orientation(1,1) * dimy) + Math::abs(orientation(1,2) * dimz);
//VecReal z = Math::abs(orientation(2,0) * dimx) + Math::abs(orientation(2,1) * dimy) + Math::abs(orientation(2,2) * dimz);
//set(-x + translation[0], -y + translation[1], -z + translation[2], x + translation[0], y + translation[1], z + translation[2]);
//}
//void transform(const Mat33& orientation, const Vec3& translation)
//{
//// convert to center and extents form
//Vec3 center, extents;
//getCenter(center);
//getExtents(extents);
//center = orientation * center + translation;
//boundsOfOBB(orientation, center, extents);
//}
bool isEmpty() const
{
// Consistency condition for (Min, Max) boxes: min < max
// TODO: PT: should we test against the explicit pattern ?
if(minimum.x < maximum.x) return false;
if(minimum.y < maximum.y) return false;
if(minimum.z < maximum.z) return false;
return true;
}
bool intersects(const Bounds3& b) const
{
if ((b.minimum.x > maximum.x) || (minimum.x > b.maximum.x)) return false;
if ((b.minimum.y > maximum.y) || (minimum.y > b.maximum.y)) return false;
if ((b.minimum.z > maximum.z) || (minimum.z > b.maximum.z)) return false;
return true;
}
bool intersects2D(const Bounds3& b, unsigned axis) const
{
// TODO: PT: could be static and like this:
// static unsigned i[3] = { 1,2,0,1 };
// const unsigned ii = i[axis];
// const unsigned jj = i[axis+1];
const unsigned i[3] = { 1,0,0 };
const unsigned j[3] = { 2,2,1 };
const unsigned ii = i[axis];
const unsigned jj = j[axis];
if ((b.minimum[ii] > maximum[ii]) || (minimum[ii] > b.maximum[ii])) return false;
if ((b.minimum[jj] > maximum[jj]) || (minimum[jj] > b.maximum[jj])) return false;
return true;
}
bool contain(const Vec3& v) const
{
if ((v.x < minimum.x) || (v.x > maximum.x)) return false;
if ((v.y < minimum.y) || (v.y > maximum.y)) return false;
if ((v.z < minimum.z) || (v.z > maximum.z)) return false;
return true;
}
void getCenter(Vec3& center) const
{
center.add(minimum,maximum);
center *= VecReal(0.5);
}
void getDimensions(Vec3& dims) const
{
dims.subtract(maximum,minimum);
}
void getExtents(Vec3& extents) const
{
extents.subtract(maximum,minimum);
extents *= VecReal(0.5);
}
void setCenterExtents(const Vec3& c, const Vec3& e)
{
minimum = c - e;
maximum = c + e;
}
void scale(VecReal _scale)
{
Vec3 center, extents;
getCenter(center);
getExtents(extents);
setCenterExtents(center, extents * _scale);
}
void fatten(VecReal distance)
{
minimum.x -= distance;
minimum.y -= distance;
minimum.z -= distance;
maximum.x += distance;
maximum.y += distance;
maximum.z += distance;
}
};
}
#endif

View File

@ -0,0 +1,100 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of NVIDIA CORPORATION nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ``AS IS'' AND ANY
// EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
// CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
// EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
// OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// Copyright (c) 2018 NVIDIA Corporation. All rights reserved.
#ifndef PLANE_H
#define PLANE_H
#include "Vec3.H"
// Singe / VecReal Precision Vec 3
// Matthias Mueller
// derived from Plane
namespace M
{
class Plane
{
public:
Plane() {}
Plane(VecReal nx, VecReal ny, VecReal nz, VecReal distance)
: n(nx, ny, nz)
, d(distance)
{}
Plane(const Vec3& normal, VecReal distance)
: n(normal)
, d(distance)
{}
Plane(const Vec3& point, const Vec3& normal)
: n(normal)
, d(-point.dot(n)) // p satisfies normal.dot(p) + d = 0
{
}
Plane(const Vec3& p0, const Vec3& p1, const Vec3& p2)
{
n = (p1 - p0).cross(p2 - p0).getNormalized();
d = -p0.dot(n);
}
VecReal distance(const Vec3& p) const
{
return p.dot(n) + d;
}
bool contains(const Vec3& p) const
{
return vecAbs(distance(p)) < (1.0e-7f);
}
Vec3 project(const Vec3 & p) const
{
return p - n * distance(p);
}
Vec3 pointInPlane() const
{
return -n*d;
}
void normalize()
{
VecReal denom = 1.0f / n.magnitude();
n *= denom;
d *= denom;
}
Vec3 n; //!< The normal to the plane
VecReal d; //!< The distance from the origin
};
}
#endif

View File

@ -0,0 +1,328 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of NVIDIA CORPORATION nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ``AS IS'' AND ANY
// EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
// CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
// EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
// OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// Copyright (c) 2018 NVIDIA Corporation. All rights reserved.
#ifndef QUAT_H
#define QUAT_H
// Singe / VecReal Precision Vec 3
// Matthias Mueller
// derived from Quat.h
#include "Vec3.h"
namespace M
{
class Quat
{
public:
Quat() { }
VecReal x,y,z,w;
Quat(VecReal nx, VecReal ny, VecReal nz, VecReal nw) : x(nx),y(ny),z(nz),w(nw) {}
Quat(VecReal angleRadians, const Vec3& unitAxis)
{
const VecReal a = angleRadians * 0.5f;
const VecReal s = vecSin(a);
w = cos(a);
x = unitAxis.x * s;
y = unitAxis.y * s;
z = unitAxis.z * s;
}
Quat(const Quat& v): x(v.x), y(v.y), z(v.z), w(v.w) {}
void toRadiansAndUnitAxis(VecReal& angle, Vec3& axis) const
{
const VecReal quatEpsilon = VecReal(1.0e-8f);
const VecReal s2 = x*x+y*y+z*z;
if(s2<quatEpsilon*quatEpsilon) // can't extract a sensible axis
{
angle = 0;
axis = Vec3(1,0,0);
}
else
{
const VecReal s = 1.0f / vecSqrt(s2);
axis = Vec3(x,y,z) * s;
angle = vecAbs(w)<quatEpsilon ? VEC_PI : vecAtan2(s2*s, w) * 2;
}
}
/**
\brief Gets the angle between this quat and the identity quaternion.
<b>Unit:</b> Radians
*/
VecReal getAngle() const
{
return vecACos(w) * VecReal(2);
}
/**
\brief Gets the angle between this quat and the argument
<b>Unit:</b> Radians
*/
VecReal getAngle(const Quat& q) const
{
return vecACos(dot(q)) * VecReal(2);
}
/**
\brief This is the squared 4D vector length, should be 1 for unit quaternions.
*/
VecReal magnitudeSquared() const
{
return x*x + y*y + z*z + w*w;
}
/**
\brief returns the scalar product of this and other.
*/
VecReal dot(const Quat& v) const
{
return x * v.x + y * v.y + z * v.z + w * v.w;
}
Quat getNormalized() const
{
const VecReal s = (VecReal)1.0/magnitude();
return Quat(x*s, y*s, z*s, w*s);
}
VecReal magnitude() const
{
return vecSqrt(magnitudeSquared());
}
//modifiers:
/**
\brief maps to the closest unit quaternion.
*/
VecReal normalize() // convert this Quat to a unit quaternion
{
const VecReal mag = magnitude();
if (mag)
{
const VecReal imag = VecReal(1) / mag;
x *= imag;
y *= imag;
z *= imag;
w *= imag;
}
return mag;
}
/*
\brief returns the conjugate.
\note for unit quaternions, this is the inverse.
*/
Quat getConjugate() const
{
return Quat(-x,-y,-z,w);
}
/*
\brief returns imaginary part.
*/
Vec3 getImaginaryPart() const
{
return Vec3(x,y,z);
}
/** brief computes rotation of x-axis */
Vec3 getBasisVector0() const
{
// return rotate(Vec3(1,0,0));
const VecReal x2 = x*(VecReal)2.0;
const VecReal w2 = w*(VecReal)2.0;
return Vec3( (w * w2) - 1.0f + x*x2,
(z * w2) + y*x2,
(-y * w2) + z*x2);
}
/** brief computes rotation of y-axis */
Vec3 getBasisVector1() const
{
// return rotate(Vec3(0,1,0));
const VecReal y2 = y*(VecReal)2.0;
const VecReal w2 = w*(VecReal)2.0;
return Vec3( (-z * w2) + x*y2,
(w * w2) - 1.0f + y*y2,
(x * w2) + z*y2);
}
/** brief computes rotation of z-axis */
Vec3 getBasisVector2() const
{
// return rotate(Vec3(0,0,1));
const VecReal z2 = z*(VecReal)2.0;
const VecReal w2 = w*(VecReal)2.0;
return Vec3( (y * w2) + x*z2,
(-x * w2) + y*z2,
(w * w2) - 1.0f + z*z2);
}
/**
rotates passed vec by this (assumed unitary)
*/
const Vec3 rotate(const Vec3& v) const
// const Vec3 rotate(const Vec3& v) const
{
const VecReal vx = (VecReal)2.0*v.x;
const VecReal vy = (VecReal)2.0*v.y;
const VecReal vz = (VecReal)2.0*v.z;
const VecReal w2 = w*w-(VecReal)0.5;
const VecReal dot2 = (x*vx + y*vy +z*vz);
return Vec3
(
(vx*w2 + (y * vz - z * vy)*w + x*dot2),
(vy*w2 + (z * vx - x * vz)*w + y*dot2),
(vz*w2 + (x * vy - y * vx)*w + z*dot2)
);
/*
const Vec3 qv(x,y,z);
return (v*(w*w-0.5f) + (qv.cross(v))*w + qv*(qv.dot(v)))*2;
*/
}
/**
inverse rotates passed vec by this (assumed unitary)
*/
const Vec3 rotateInv(const Vec3& v) const
// const Vec3 rotateInv(const Vec3& v) const
{
const VecReal vx = (VecReal)2.0*v.x;
const VecReal vy = (VecReal)2.0*v.y;
const VecReal vz = (VecReal)2.0*v.z;
const VecReal w2 = w*w-(VecReal)0.5;
const VecReal dot2 = (x*vx + y*vy +z*vz);
return Vec3
(
(vx*w2 - (y * vz - z * vy)*w + x*dot2),
(vy*w2 - (z * vx - x * vz)*w + y*dot2),
(vz*w2 - (x * vy - y * vx)*w + z*dot2)
);
// const Vec3 qv(x,y,z);
// return (v*(w*w-0.5f) - (qv.cross(v))*w + qv*(qv.dot(v)))*2;
}
/**
\brief Assignment operator
*/
Quat& operator=(const Quat& p) { x = p.x; y = p.y; z = p.z; w = p.w; return *this; }
Quat& operator*= (const Quat& q)
{
const VecReal tx = w*q.x + q.w*x + y*q.z - q.y*z;
const VecReal ty = w*q.y + q.w*y + z*q.x - q.z*x;
const VecReal tz = w*q.z + q.w*z + x*q.y - q.x*y;
w = w*q.w - q.x*x - y*q.y - q.z*z;
x = tx;
y = ty;
z = tz;
return *this;
}
Quat& operator+= (const Quat& q)
{
x+=q.x;
y+=q.y;
z+=q.z;
w+=q.w;
return *this;
}
Quat& operator-= (const Quat& q)
{
x-=q.x;
y-=q.y;
z-=q.z;
w-=q.w;
return *this;
}
Quat& operator*= (const VecReal s)
{
x*=s;
y*=s;
z*=s;
w*=s;
return *this;
}
/** quaternion multiplication */
Quat operator*(const Quat& q) const
{
return Quat(w*q.x + q.w*x + y*q.z - q.y*z,
w*q.y + q.w*y + z*q.x - q.z*x,
w*q.z + q.w*z + x*q.y - q.x*y,
w*q.w - x*q.x - y*q.y - z*q.z);
}
/** quaternion addition */
Quat operator+(const Quat& q) const
{
return Quat(x+q.x,y+q.y,z+q.z,w+q.w);
}
/** quaternion subtraction */
Quat operator-() const
{
return Quat(-x,-y,-z,-w);
}
Quat operator-(const Quat& q) const
{
return Quat(x-q.x,y-q.y,z-q.z,w-q.w);
}
Quat operator*(VecReal r) const
{
return Quat(x*r,y*r,z*r,w*r);
}
static Quat createIdentity() { return Quat(0,0,0,1); }
};
}
#endif

View File

@ -0,0 +1,121 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of NVIDIA CORPORATION nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ``AS IS'' AND ANY
// EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
// CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
// EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
// OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// Copyright (c) 2018 NVIDIA Corporation. All rights reserved.
#ifndef TRANSFORM_H
#define TRANSFORM_H
#include "Vec3.h"
#include "Quat.h"
#include "Plane.h"
// Singe / VecVecReal Precision Vec 3
// Matthias Mueller
// derived from NxVec3.h
namespace M
{
class Transform
{
public:
Quat q;
Vec3 p;
Transform() {};
Transform(const Vec3& position): q(0, 0, 0, 1), p(position) {}
Transform(const Quat& orientation): q(orientation), p(0, 0, 0) {}
Transform(const Vec3& p0, const Quat& q0): q(q0), p(p0) {}
Transform operator*(const Transform& x) const
{
return transform(x);
}
Transform getInverse() const
{
return Transform(q.rotateInv(-p),q.getConjugate());
}
Vec3 transform(const Vec3& input) const
{
return q.rotate(input) + p;
}
Vec3 transformInv(const Vec3& input) const
{
return q.rotateInv(input-p);
}
Vec3 rotate(const Vec3& input) const
{
return q.rotate(input);
}
Vec3 rotateInv(const Vec3& input) const
{
return q.rotateInv(input);
}
Transform transform(const Transform& src) const
{
return Transform(q.rotate(src.p) + p, q*src.q);
}
Transform transformInv(const Transform& src) const
{
Quat qinv = q.getConjugate();
return Transform(qinv.rotate(src.p - p), qinv*src.q);
}
static Transform createIdentity()
{
return Transform(Vec3(0));
}
Plane transform(const Plane& plane) const
{
Vec3 transformedNormal = rotate(plane.n);
return Plane(transformedNormal, plane.d - p.dot(transformedNormal));
}
Plane inverseTransform(const Plane& plane) const
{
Vec3 transformedNormal = rotateInv(plane.n);
return Plane(transformedNormal, plane.d + p.dot(plane.n));
}
Transform getNormalized() const
{
return Transform(p, q.getNormalized());
}
};
}
#endif

View File

@ -0,0 +1,517 @@
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of NVIDIA CORPORATION nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ``AS IS'' AND ANY
// EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
// CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
// EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
// OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// Copyright (c) 2018 NVIDIA Corporation. All rights reserved.
#ifndef VEC3_H
#define VEC3_H
#include <math.h>
// Singe / VecReal Precision Vec 3
// Matthias Mueller
// derived from NxVec3.h
namespace M
{
#define VEC3_DOUBLE 0
#if VEC3_DOUBLE
typedef double VecReal;
#define MAX_VEC_REAL DBL_MAX
#define MIN_VEC_REAL -DBL_MAX
#define VEC_PI 3.14159265358979323846
inline int vecFloor(VecReal f ) { return (int)::floor(f); }
inline VecReal vecSqrt(VecReal f) { return ::sqrt(f); }
inline VecReal vecSin(VecReal f) { return ::sin(f); }
inline VecReal vecCos(VecReal f) { return ::cos(f); }
inline VecReal vecAbs(VecReal f) { return ::abs(f); }
inline VecReal vecAtan2(VecReal y, VecReal x) { return ::atan2(y, x); }
inline VecReal vecASin(VecReal f) { return ::asin(f); }
inline VecReal vecACos(VecReal f) { return ::acos(f); }
inline VecReal vecATan(VecReal f) { return ::atan(f); }
#else
typedef float VecReal;
#define MAX_VEC_REAL FLT_MAX
#define MIN_VEC_REAL -FLT_MAX
#define VEC_PI 3.14159265358979323846f
inline int vecFloor(VecReal f ) { return (int)::floorf(f); }
inline VecReal vecSqrt(VecReal f) { return ::sqrtf(f); }
inline VecReal vecSin(VecReal f) { return ::sinf(f); }
inline VecReal vecCos(VecReal f) { return ::cosf(f); }
inline VecReal vecAbs(VecReal f) { return ::fabs(f); }
inline VecReal vecAtan2(VecReal y, VecReal x) { return ::atan2f(y, x); }
inline VecReal vecASin(VecReal f) { return ::asinf(f); }
inline VecReal vecACos(VecReal f) { return ::acosf(f); }
inline VecReal vecATan(VecReal f) { return ::atanf(f); }
#endif
/**
\brief Enum to classify an axis.
*/
enum DAxisType
{
D_AXIS_PLUS_X,
D_AXIS_MINUS_X,
D_AXIS_PLUS_Y,
D_AXIS_MINUS_Y,
D_AXIS_PLUS_Z,
D_AXIS_MINUS_Z,
D_AXIS_ARBITRARY
};
// -------------------------------------------------------------------------------------
class Vec3
{
public:
VecReal x,y,z;
Vec3() {};
Vec3(VecReal _x, VecReal _y, VecReal _z) : x(_x), y(_y), z(_z) {}
Vec3(const VecReal v[]) : x(v[0]), y(v[1]), z(v[2]) {}
const VecReal* Vec3::get() const { return &x;}
VecReal* get() { return &x; }
void get(VecReal * v) const
{
v[0] = x;
v[1] = y;
v[2] = z;
}
VecReal& operator[](int index)
{
return (&x)[index];
}
const VecReal operator[](int index) const
{
return (&x)[index];
}
void setx(const VecReal & d)
{
x = d;
}
void sety(const VecReal & d)
{
y = d;
}
void setz(const VecReal & d)
{
z = d;
}
Vec3 getNormalized() const
{
const VecReal m = magnitudeSquared();
return m>0 ? *this * 1.0 / vecSqrt(m) : Vec3(0,0,0);
}
//Operators
bool operator< (const Vec3&v) const
{
return ((x < v.x)&&(y < v.y)&&(z < v.z));
}
bool operator==(const Vec3& v) const
{
return ((x == v.x)&&(y == v.y)&&(z == v.z));
}
bool operator!=(const Vec3& v) const
{
return ((x != v.x)||(y != v.y)||(z != v.z));
}
//Methods
void set(const Vec3 & v)
{
x = v.x;
y = v.y;
z = v.z;
}
void setNegative(const Vec3 & v)
{
x = -v.x;
y = -v.y;
z = -v.z;
}
void setNegative()
{
x = -x;
y = -y;
z = -z;
}
void set(const VecReal * v)
{
x = v[0];
y = v[1];
z = v[2];
}
void set(VecReal _x, VecReal _y, VecReal _z)
{
this->x = _x;
this->y = _y;
this->z = _z;
}
void set(VecReal v)
{
x = v;
y = v;
z = v;
}
void zero()
{
x = y = z = 0.0;
}
void setPlusInfinity()
{
x = y = z = MAX_VEC_REAL;
}
void setMinusInfinity()
{
x = y = z = MIN_VEC_REAL;
}
void max(const Vec3 & v)
{
x = x > v.x ? x : v.x;
y = y > v.y ? y : v.y;
z = z > v.z ? z : v.z;
}
void min(const Vec3 & v)
{
x = x < v.x ? x : v.x;
y = y < v.y ? y : v.y;
z = z < v.z ? z : v.z;
}
void add(const Vec3 & a, const Vec3 & b)
{
x = a.x + b.x;
y = a.y + b.y;
z = a.z + b.z;
}
void subtract(const Vec3 &a, const Vec3 &b)
{
x = a.x - b.x;
y = a.y - b.y;
z = a.z - b.z;
}
void arrayMultiply(const Vec3 &a, const Vec3 &b)
{
x = a.x * b.x;
y = a.y * b.y;
z = a.z * b.z;
}
void multiply(VecReal s, const Vec3 & a)
{
x = a.x * s;
y = a.y * s;
z = a.z * s;
}
void multiplyAdd(VecReal s, const Vec3 & a, const Vec3 & b)
{
x = s * a.x + b.x;
y = s * a.y + b.y;
z = s * a.z + b.z;
}
VecReal normalize()
{
VecReal m = magnitude();
if (m)
{
const VecReal il = VecReal(1.0) / m;
x *= il;
y *= il;
z *= il;
}
return m;
}
void setMagnitude(VecReal length)
{
VecReal m = magnitude();
if(m)
{
VecReal newLength = length / m;
x *= newLength;
y *= newLength;
z *= newLength;
}
}
DAxisType snapToClosestAxis()
{
const VecReal almostOne = 0.999999f;
if(x >= almostOne) { set( 1.0f, 0.0f, 0.0f); return D_AXIS_PLUS_X ; }
else if(x <= -almostOne) { set(-1.0f, 0.0f, 0.0f); return D_AXIS_MINUS_X; }
else if(y >= almostOne) { set( 0.0f, 1.0f, 0.0f); return D_AXIS_PLUS_Y ; }
else if(y <= -almostOne) { set( 0.0f, -1.0f, 0.0f); return D_AXIS_MINUS_Y; }
else if(z >= almostOne) { set( 0.0f, 0.0f, 1.0f); return D_AXIS_PLUS_Z ; }
else if(z <= -almostOne) { set( 0.0f, 0.0f, -1.0f); return D_AXIS_MINUS_Z; }
else return D_AXIS_ARBITRARY;
}
unsigned int closestAxis() const
{
const VecReal* vals = &x;
unsigned int m = 0;
if(abs(vals[1]) > abs(vals[m])) m = 1;
if(abs(vals[2]) > abs(vals[m])) m = 2;
return m;
}
//const methods
//bool isFinite() const
//{
// return NxMath::isFinite(x) && NxMath::isFinite(y) && NxMath::isFinite(z);
//}
VecReal dot(const Vec3 &v) const
{
return x * v.x + y * v.y + z * v.z;
}
bool sameDirection(const Vec3 &v) const
{
return x*v.x + y*v.y + z*v.z >= 0.0f;
}
VecReal magnitude() const
{
return sqrt(x * x + y * y + z * z);
}
VecReal magnitudeSquared() const
{
return x * x + y * y + z * z;
}
VecReal distance(const Vec3 & v) const
{
VecReal dx = x - v.x;
VecReal dy = y - v.y;
VecReal dz = z - v.z;
return sqrt(dx * dx + dy * dy + dz * dz);
}
VecReal distanceSquared(const Vec3 &v) const
{
VecReal dx = x - v.x;
VecReal dy = y - v.y;
VecReal dz = z - v.z;
return dx * dx + dy * dy + dz * dz;
}
void cross(const Vec3 &left, const Vec3 & right) //prefered version, w/o temp object.
{
// temps needed in case left or right is this.
VecReal a = (left.y * right.z) - (left.z * right.y);
VecReal b = (left.z * right.x) - (left.x * right.z);
VecReal c = (left.x * right.y) - (left.y * right.x);
x = a;
y = b;
z = c;
}
bool equals(const Vec3 & v, VecReal epsilon) const
{
return
abs(x - v.x) < epsilon &&
abs(y - v.y) < epsilon &&
abs(z - v.z) < epsilon;
}
Vec3 operator -() const
{
return Vec3(-x, -y, -z);
}
Vec3 operator +(const Vec3 & v) const
{
return Vec3(x + v.x, y + v.y, z + v.z); // RVO version
}
Vec3 operator -(const Vec3 & v) const
{
return Vec3(x - v.x, y - v.y, z - v.z); // RVO version
}
Vec3 operator *(VecReal f) const
{
return Vec3(x * f, y * f, z * f); // RVO version
}
Vec3 operator /(VecReal f) const
{
f = VecReal(1.0) / f; return Vec3(x * f, y * f, z * f);
}
Vec3& operator +=(const Vec3& v)
{
x += v.x;
y += v.y;
z += v.z;
return *this;
}
Vec3& operator -=(const Vec3& v)
{
x -= v.x;
y -= v.y;
z -= v.z;
return *this;
}
Vec3& operator *=(VecReal f)
{
x *= f;
y *= f;
z *= f;
return *this;
}
Vec3& operator /=(VecReal f)
{
f = 1.0f/f;
x *= f;
y *= f;
z *= f;
return *this;
}
Vec3 cross(const Vec3& v) const
{
Vec3 temp;
temp.cross(*this,v);
return temp;
}
Vec3 operator^(const Vec3& v) const
{
Vec3 temp;
temp.cross(*this,v);
return temp;
}
VecReal operator|(const Vec3& v) const
{
return x * v.x + y * v.y + z * v.z;
}
};
/**
scalar pre-multiplication
*/
inline Vec3 operator *(VecReal f, const Vec3& v)
{
return Vec3(f * v.x, f * v.y, f * v.z);
}
}
/** @} */
#endif