AxisAngle FromQuaternion
All checks were successful
Run ReCI Build Test / Explore-Gitea-Actions (push) Successful in 5m52s
Build Docs With Doxygen / Explore-Gitea-Actions (push) Successful in 24s

This commit is contained in:
2024-11-19 09:13:37 -05:00
parent 2caa4c8412
commit aaea5ff53e
6 changed files with 240 additions and 282 deletions

View File

@@ -13,6 +13,7 @@ namespace J3ML::LinearAlgebra {
class J3ML::LinearAlgebra::AxisAngle {
public:
Vector3 axis;
// Radians.
float angle;
public:
AxisAngle();

View File

@@ -4,256 +4,237 @@
#include <J3ML/Algorithm/RNG.hpp>
#include <cmath>
namespace J3ML::LinearAlgebra
{
class Quaternion {
public:
/// The identity quaternion performs no rotation when applied to a vector.
static const Quaternion Identity;
/// A compile-time constant Quaternion with the value (NAN, NAN, NAN, NAN).
/// For this constant, each element has the value of quiet NAN, or Not-A-Number.
/// @note Never compare a Quaternion to this value! Due to how IEEE floats work, "nan == nan" returns false!
/// That is, nothing is equal to NaN, not even NaN itself!
static const Quaternion NaN;
public:
/// The default constructor does not initialize any member values.
Quaternion();
/// Copy constructor
Quaternion(const Quaternion &rhs) = default;
/// Constructs a quaternion from the given data buffer.
/// @param data An array of four floats to use for the quaternion, in the order 'x,y,z,w.' (== 'i,j,k,w')
explicit Quaternion(const float *data);
namespace J3ML::LinearAlgebra {
class Quaternion;
}
explicit Quaternion(const Matrix3x3& rotationMtrx);
explicit Quaternion(const Matrix4x4& rotationMtrx);
class J3ML::LinearAlgebra::Quaternion {
public:
float x;
float y;
float z;
float w;
public:
/// The identity quaternion performs no rotation when applied to a vector.
static const Quaternion Identity;
/// A compile-time constant Quaternion with the value (NAN, NAN, NAN, NAN).
/// For this constant, each element has the value of quiet NAN, or Not-A-Number.
/// @note Never compare a Quaternion to this value! Due to how IEEE floats work, "nan == nan" returns false!
/// That is, nothing is equal to NaN, not even NaN itself!
static const Quaternion NaN;
public:
/// The default constructor does not initialize any member values.
Quaternion() = default;
/// Copy constructor
Quaternion(const Quaternion &rhs);
/// Quaternion from Matrix3x3
explicit Quaternion(const Matrix3x3& ro_mat);
/// Quaternion from Matrix4x4 RotatePart.
explicit Quaternion(const Matrix4x4& ro_mat);
/// Quaternion from EulerAngleXYZ.
explicit Quaternion(const EulerAngleXYZ& rhs);
/// Quaternion from AxisAngle.
explicit Quaternion(const AxisAngle& angle);
/// Quaternion from Vector4 (no conversion).
explicit Quaternion(const Vector4& vector4);
/// @param x The factor of i.
/// @param y The factor of j.
/// @param z The factor of k.
/// @param w The scalar factor (or 'w').
/// @note The input data is not normalized after construction, this has to be done manually.
Quaternion(float X, float Y, float Z, float W);
/// @param x The factor of i.
/// @param y The factor of j.
/// @param z The factor of k.
/// @param w The scalar factor (or 'w').
/// @note The input data is not normalized after construction, this has to be done manually.
Quaternion(float X, float Y, float Z, float W);
Quaternion(const EulerAngleXYZ& rhs);
/// Creates a LookAt quaternion.
/** A LookAt quaternion is a quaternion that orients an object to face towards a specified target direction.
@param localForward Specifies the forward direction in the local space of the object. This is the direction
the model is facing at in its own local/object space, often +X(1,0,0), +Y(0,1,0), or +Z(0,0,1).
The vector to pass in here depends on the conventions you or your modeling software is using, and it is best
to pick one convention for all your objects, and be consistent.
This input parameter must be a normalized vector.
@param targetDirection Specifies the desired world space direction the object should look at. This function
will compute a quaternion which will rotate the localForward vector to orient towards this targetDirection
vector. This input parameter must be a normalized vector.
@param localUp Specifies the up direction in the local space of the object. This is the up direction the model
was authored in, often +Y (0,1,0) or +Z (0,0,1). The vector to pass in here depends on the conventions you
or your modeling software is using, and it is best to pick one convention for all your objects, and be
consistent. This input parameter must be a normalized vector. This vector must be perpendicular to the
vector localForward, i.e. localForward.Dot(localUp) == 0.
@param worldUp Specifies the global up direction of the scene in world space. Simply rotating one vector to
coincide with another (localForward->targetDirection) would cause the up direction of the resulting
orientation to drift (e.g. the model could be looking at its target its head slanted sideways). To keep
the up direction straight, this function orients the localUp direction of the model to point towards
the specified worldUp direction (as closely as possible). The worldUp and targetDirection vectors cannot be
collinear, but they do not need to be perpendicular either.
@return A quaternion that maps the given local space forward direction vector to point towards the given target
direction, and the given local up direction towards the given target world up direction. For the returned
quaternion Q it holds that M * localForward = targetDirection, and M * localUp lies in the plane spanned
by the vectors targetDirection and worldUp.
@see RotateFromTo() */
static Quaternion LookAt(const Vector3& localForward, const Vector3& targetDirection, const Vector3& localUp, const Vector3& worldUp);
/// Constructs this quaternion by specifying a rotation axis and the amount of rotation to be performed about that axis
/// @param rotationAxis The normalized rotation axis to rotate about. If using Vector4 version of the constructor, the w component of this vector must be 0.
/// @param rotationAngleRadians The angle to rotate by, in radians. For example, Pi/4.f equals to 45 degrees, Pi/2.f is 90 degrees, etc.
/// @see DegToRad()
Quaternion(const Vector3 &rotationAxis, float rotationAngleRadians);
Quaternion(const Vector4 &rotationAxis, float rotationAngleRadians);
/// Creates a new quaternion that rotates about the positive X axis by the given rotation.
static Quaternion RotateX(float rad);
/// Creates a new quaternion that rotates about the positive Y axis by the given rotation.
static Quaternion RotateY(float rad);
/// Creates a new quaternion that rotates about the positive Z axis by the given rotation.
static Quaternion RotateZ(float rad);
explicit Quaternion(const Vector4& vector4);
explicit Quaternion(const AxisAngle& angle);
/// Creates a new quaternion that rotates sourceDirection vector (in world space) to coincide with the
/// targetDirection vector (in world space).
/// Rotation is performed about the origin.
/// The vectors sourceDirection and targetDirection are assumed to be normalized.
/// @note There are multiple such rotations - this function returns the rotation that has the shortest angle
/// (when decomposed to axis-angle notation).
static Quaternion RotateFromTo(const Vector3& sourceDirection, const Vector3& targetDirection);
static Quaternion RotateFromTo(const Vector4& sourceDirection, const Vector4& targetDirection);
/// Creates a LookAt quaternion.
/** A LookAt quaternion is a quaternion that orients an object to face towards a specified target direction.
@param localForward Specifies the forward direction in the local space of the object. This is the direction
the model is facing at in its own local/object space, often +X(1,0,0), +Y(0,1,0), or +Z(0,0,1).
The vector to pass in here depends on the conventions you or your modeling software is using, and it is best
to pick one convention for all your objects, and be consistent.
This input parameter must be a normalized vector.
@param targetDirection Specifies the desired world space direction the object should look at. This function
will compute a quaternion which will rotate the localForward vector to orient towards this targetDirection
vector. This input parameter must be a normalized vector.
@param localUp Specifies the up direction in the local space of the object. This is the up direction the model
was authored in, often +Y (0,1,0) or +Z (0,0,1). The vector to pass in here depends on the conventions you
or your modeling software is using, and it is best to pick one convention for all your objects, and be
consistent. This input parameter must be a normalized vector. This vector must be perpendicular to the
vector localForward, i.e. localForward.Dot(localUp) == 0.
@param worldUp Specifies the global up direction of the scene in world space. Simply rotating one vector to
coincide with another (localForward->targetDirection) would cause the up direction of the resulting
orientation to drift (e.g. the model could be looking at its target its head slanted sideways). To keep
the up direction straight, this function orients the localUp direction of the model to point towards
the specified worldUp direction (as closely as possible). The worldUp and targetDirection vectors cannot be
collinear, but they do not need to be perpendicular either.
@return A quaternion that maps the given local space forward direction vector to point towards the given target
direction, and the given local up direction towards the given target world up direction. For the returned
quaternion Q it holds that M * localForward = targetDirection, and M * localUp lies in the plane spanned
by the vectors targetDirection and worldUp.
@see RotateFromTo() */
static Quaternion LookAt(const Vector3& localForward, const Vector3& targetDirection, const Vector3& localUp, const Vector3& worldUp);
/// Creates a new Quaternion that rotates about the given axis by the given angle.
static Quaternion RotateAxisAngle(const AxisAngle& axisAngle);
/// Creates a new quaternion that rotates about the positive X axis by the given rotation.
static Quaternion RotateX(float angleRadians);
/// Creates a new quaternion that rotates about the positive Y axis by the given rotation.
static Quaternion RotateY(float angleRadians);
/// Creates a new quaternion that rotates about the positive Z axis by the given rotation.
static Quaternion RotateZ(float angleRadians);
/// Creates a new quaternion that rotates sourceDirection vector (in world space) to coincide with the
/// targetDirection vector (in world space).
/// Rotation is performed about the origin.
/// The vectors sourceDirection and targetDirection are assumed to be normalized.
/// @note There are multiple such rotations - this function returns the rotation that has the shortest angle
/// (when decomposed to axis-angle notation).
static Quaternion RotateFromTo(const Vector3& sourceDirection, const Vector3& targetDirection);
static Quaternion RotateFromTo(const Vector4& sourceDirection, const Vector4& targetDirection);
/// Creates a new quaternion that
/// 1. rotates sourceDirection vector to coincide with the targetDirection vector, and then
/// 2. rotates sourceDirection2 (which was transformed by 1.) to targetDirection2, but keeping the constraint that
/// sourceDirection must look at targetDirection
static Quaternion RotateFromTo(const Vector3& sourceDirection, const Vector3& targetDirection, const Vector3& sourceDirection2, const Vector3& targetDirection2);
/// Creates a new quaternion that
/// 1. rotates sourceDirection vector to coincide with the targetDirection vector, and then
/// 2. rotates sourceDirection2 (which was transformed by 1.) to targetDirection2, but keeping the constraint that
/// sourceDirection must look at targetDirection
static Quaternion RotateFromTo(const Vector3& sourceDirection, const Vector3& targetDirection, const Vector3& sourceDirection2, const Vector3& targetDirection2);
/// Returns a uniformly random unitary quaternion.
static Quaternion RandomRotation(RNG &rng);
public:
void SetFromAxisAngle(const Vector3 &vector3, float between);
/// Returns a uniformly random unitary quaternion.
static Quaternion RandomRotation(RNG &rng);
public:
/// Inverses this quaternion in-place.
/// @note For optimization purposes, this function assumes that the quaternion is unitary, in which
/// case the inverse of the quaternion is simply just the same as its conjugate.
/// This function does not detect whether the operation succeeded or failed.
void Inverse();
void SetFromAxisAngle(const Vector4 &vector4, float between);
void SetFrom(const AxisAngle& angle);
/// Returns an inverted copy of this quaternion.
[[nodiscard]] Quaternion Inverted() const;
/// Computes the conjugate of this quaternion in-place.
void Conjugate();
/// Returns a conjugated copy of this quaternion.
[[nodiscard]] Quaternion Conjugated() const;
/// Inverses this quaternion in-place.
/// @note For optimization purposes, this function assumes that the quaternion is unitary, in which
/// case the inverse of the quaternion is simply just the same as its conjugate.
/// This function does not detect whether the operation succeeded or failed.
void Inverse();
/// Inverses this quaternion in-place.
/// Call this function when the quaternion is not known beforehand to be normalized.
/// This function computes the inverse proper, and normalizes the result.
/// @note Because of the normalization, it does not necessarily hold that q * q.InverseAndNormalize() == id.
/// @return Returns the old length of this quaternion (not the old length of the inverse quaternion).
float InverseAndNormalize();
/// Returns an inverted copy of this quaternion.
[[nodiscard]] Quaternion Inverted() const;
/// Computes the conjugate of this quaternion in-place.
void Conjugate();
/// Returns a conjugated copy of this quaternion.
[[nodiscard]] Quaternion Conjugated() const;
/// Returns the local +X axis in the post-transformed coordinate space. This is the same as transforming the vector (1,0,0) by this quaternion.
[[nodiscard]] Vector3 WorldX() const;
/// Returns the local +Y axis in the post-transformed coordinate space. This is the same as transforming the vector (0,1,0) by this quaternion.
[[nodiscard]] Vector3 WorldY() const;
/// Returns the local +Z axis in the post-transformed coordinate space. This is the same as transforming the vector (0,0,1) by this quaternion.
[[nodiscard]] Vector3 WorldZ() const;
/// Returns the axis of rotation for this quaternion.
[[nodiscard]] Vector3 Axis() const;
/// Inverses this quaternion in-place.
/// Call this function when the quaternion is not known beforehand to be normalized.
/// This function computes the inverse proper, and normalizes the result.
/// @note Because of the normalization, it does not necessarily hold that q * q.InverseAndNormalize() == id.
/// @return Returns the old length of this quaternion (not the old length of the inverse quaternion).
float InverseAndNormalize();
/// Returns the angle of rotation for this quaternion, in radians.
[[nodiscard]] float Angle() const;
/// Returns the local +X axis in the post-transformed coordinate space. This is the same as transforming the vector (1,0,0) by this quaternion.
[[nodiscard]] Vector3 WorldX() const;
/// Returns the local +Y axis in the post-transformed coordinate space. This is the same as transforming the vector (0,1,0) by this quaternion.
[[nodiscard]] Vector3 WorldY() const;
/// Returns the local +Z axis in the post-transformed coordinate space. This is the same as transforming the vector (0,0,1) by this quaternion.
[[nodiscard]] Vector3 WorldZ() const;
[[nodiscard]] float LengthSquared() const;
[[nodiscard]] float Length() const;
/// Returns the axis of rotation for this quaternion.
[[nodiscard]] Vector3 Axis() const;
[[nodiscard]] Matrix3x3 ToMatrix3x3() const;
[[nodiscard]] Matrix4x4 ToMatrix4x4() const;
/// Returns the angle of rotation for this quaternion, in radians.
[[nodiscard]] float Angle() const;
[[nodiscard]] Matrix4x4 ToMatrix4x4(const Vector3 &translation) const;
[[nodiscard]] float LengthSquared() const;
[[nodiscard]] float Length() const;
[[nodiscard]] Vector3 Transform(const Vector3& vec) const;
[[nodiscard]] Vector3 Transform(float X, float Y, float Z) const;
// Note: We only transform the x,y,z components of 4D vectors, w is left untouched
[[nodiscard]] Vector4 Transform(const Vector4& vec) const;
[[nodiscard]] Vector4 Transform(float X, float Y, float Z, float W) const;
[[nodiscard]] Matrix3x3 ToMatrix3x3() const;
[[nodiscard]] Matrix4x4 ToMatrix4x4() const;
[[nodiscard]] Quaternion Lerp(const Quaternion& b, float t) const;
static Quaternion Lerp(const Quaternion &source, const Quaternion& target, float t);
[[nodiscard]] Quaternion Slerp(const Quaternion& q2, float t) const;
static Quaternion Slerp(const Quaternion &source, const Quaternion& target, float t);
[[nodiscard]] Matrix4x4 ToMatrix4x4(const Vector3 &translation) const;
/// Returns the 'from' vector rotated towards the 'to' vector by the given normalized time parameter.
/** This function slerps the given 'form' vector toward the 'to' vector.
@param from A normalized direction vector specifying the direction of rotation at t=0
@param to A normalized direction vector specifying the direction of rotation at t=1
@param t The interpolation time parameter, in the range [0, 1]. Input values outside this range are
silently clamped to the [0, 1] interval.
@return A spherical linear interpolation of the vector 'from' towards the vector 'to'. */
static Vector3 SlerpVector(const Vector3& from, const Vector3& to, float t);
[[nodiscard]] Vector3 Transform(const Vector3& vec) const;
[[nodiscard]] Vector3 Transform(float X, float Y, float Z) const;
// Note: We only transform the x,y,z components of 4D vectors, w is left untouched
[[nodiscard]] Vector4 Transform(const Vector4& vec) const;
[[nodiscard]] Vector4 Transform(float X, float Y, float Z, float W) const;
/// Returns the 'from' vector rotated towards the 'to' vector by the given absolute angle, in radians.
/** This function slerps the given 'from' vector towards the 'to' vector.
@param from A normalized direction vector specifying the direction of rotation at angleRadians=0.
@param to A normalized direction vector specifying the target direction to rotate towards.
@param angleRadians The maximum angle to rotate the 'from' vector by, in the range [0, pi]. If the
angle between 'from' and 'to' is smaller than this angle, then the vector 'to' is returned.
Input values outside this range are silently clamped to the [0, pi] interval.
@return A spherical linear interpolation of the vector 'from' towards the vector 'to'. */
static Vector3 SlerpVectorAbs(const Vector3 &from, const Vector3& to, float angleRadians);
[[nodiscard]] Quaternion Lerp(const Quaternion& b, float t) const;
static Quaternion Lerp(const Quaternion &source, const Quaternion& target, float t);
[[nodiscard]] Quaternion Slerp(const Quaternion& q2, float t) const;
static Quaternion Slerp(const Quaternion &source, const Quaternion& target, float t);
/// Normalizes this quaternion in-place.
/// @returns false if failure, true if success.
[[nodiscard]] bool Normalize();
/// Returns a normalized copy of this quaternion.
[[nodiscard]] Quaternion Normalized() const;
/// Returns the 'from' vector rotated towards the 'to' vector by the given normalized time parameter.
/** This function slerps the given 'form' vector toward the 'to' vector.
@param from A normalized direction vector specifying the direction of rotation at t=0
@param to A normalized direction vector specifying the direction of rotation at t=1
@param t The interpolation time parameter, in the range [0, 1]. Input values outside this range are
silently clamped to the [0, 1] interval.
@return A spherical linear interpolation of the vector 'from' towards the vector 'to'. */
static Vector3 SlerpVector(const Vector3& from, const Vector3& to, float t);
/// Returns true if the length of this quaternion is one.
[[nodiscard]] bool IsNormalized(float epsilon = 1e-5f) const;
[[nodiscard]] bool IsInvertible(float epsilon = 1e-3f) const;
/// Returns the 'from' vector rotated towards the 'to' vector by the given absolute angle, in radians.
/** This function slerps the given 'from' vector towards the 'to' vector.
@param from A normalized direction vector specifying the direction of rotation at angleRadians=0.
@param to A normalized direction vector specifying the target direction to rotate towards.
@param angleRadians The maximum angle to rotate the 'from' vector by, in the range [0, pi]. If the
angle between 'from' and 'to' is smaller than this angle, then the vector 'to' is returned.
Input values outside this range are silently clamped to the [0, pi] interval.
@return A spherical linear interpolation of the vector 'from' towards the vector 'to'. */
static Vector3 SlerpVectorAbs(const Vector3 &from, const Vector3& to, float angleRadians);
/// Returns true if the entries of this quaternion are all finite.
[[nodiscard]] bool IsFinite() const;
/// Normalizes this quaternion in-place.
/// Returns the old length of this quaternion, or 0 if normalization failed.
float Normalize();
/// Returns a normalized copy of this quaternion.
[[nodiscard]] Quaternion Normalized() const;
/// Returns true if this quaternion equals rhs, up to the given epsilon.
[[nodiscard]] bool Equals(const Quaternion& rhs, float epsilon = 1e-3f) const;
/// Returns true if the length of this quaternion is one.
[[nodiscard]] bool IsNormalized(float epsilon = 1e-5f) const;
[[nodiscard]] bool IsInvertible(float epsilon = 1e-3f) const;
/// Compares whether this Quaternion and the given Quaternion are identical bit-by-bit in the underlying representation.
/// @note Prefer using this over e.g. memcmp, since there can be SSE-related padding in the structures.
bool BitEquals(const Quaternion& rhs) const;
/// Returns true if the entries of this quaternion are all finite.
[[nodiscard]] bool IsFinite() const;
/// Returns true if this quaternion equals rhs, up to the given epsilon.
[[nodiscard]] bool Equals(const Quaternion& rhs, float epsilon = 1e-3f) const;
/// Compares whether this Quaternion and the given Quaternion are identical bit-by-bit in the underlying representation.
/// @note Prefer using this over e.g. memcmp, since there can be SSE-related padding in the structures.
bool BitEquals(const Quaternion& rhs) const;
/// @return A pointer to the first element (x). The data is contiguous in memory.
/// ptr[0] gives x, ptr[1] gives y, ptr[2] gives z, ptr[3] gives w.
inline float *ptr() { return &x; }
[[nodiscard]] inline const float *ptr() const { return &x; }
/// @return A pointer to the first element (x). The data is contiguous in memory.
/// ptr[0] gives x, ptr[1] gives y, ptr[2] gives z, ptr[3] gives w.
inline float *ptr() { return &x; }
[[nodiscard]] inline const float *ptr() const { return &x; }
// Multiplies two quaternions together.
// The product q1 * q2 returns a quaternion that concatenates the two orientation rotations.
// The rotation q2 is applied first before q1.
Quaternion operator * (const Quaternion& rhs) const;
// Multiplies two quaternions together.
// The product q1 * q2 returns a quaternion that concatenates the two orientation rotations.
// The rotation q2 is applied first before q1.
Quaternion operator * (const Quaternion& rhs) const;
// Unsafe
Quaternion operator * (float scalar) const;
// Unsafe
Quaternion operator * (float scalar) const;
// Unsafe
Quaternion operator / (float scalar) const;
// Unsafe
Quaternion operator / (float scalar) const;
// Transforms the given vector by this Quaternion.
Vector3 operator * (const Vector3& rhs) const;
// Transforms the given vector by this Quaternion.
Vector3 operator * (const Vector3& rhs) const;
Vector4 operator * (const Vector4& rhs) const;
Vector4 operator * (const Vector4& rhs) const;
// Divides a quaternion by another. Divison "a / b" results in a quaternion that rotates the orientation b to coincide with orientation of
Quaternion operator / (const Quaternion& rhs) const;
Quaternion operator + (const Quaternion& rhs) const;
// Divides a quaternion by another. Divison "a / b" results in a quaternion that rotates the orientation b to coincide with orientation of
Quaternion operator / (const Quaternion& rhs) const;
Quaternion operator + (const Quaternion& rhs) const;
Quaternion operator + () const;
Quaternion operator - () const;
Quaternion operator + () const;
Quaternion operator - () const;
/// Computes the dot product of this and the given quaternion.
/// Dot product is commutative.
[[nodiscard]] float Dot(const Quaternion &quaternion) const;
/// Computes the dot product of this and the given quaternion.
/// Dot product is commutative.
[[nodiscard]] float Dot(const Quaternion &quaternion) const;
/// Returns the angle between this and the target orientation (the shortest route) in radians.
[[nodiscard]] float AngleBetween(const Quaternion& target) const;
/// Returns the axis of rotation to get from this orientation to target orientation (the shortest route).
[[nodiscard]] Vector3 AxisFromTo(const Quaternion& target) const;
/// Returns the angle between this and the target orientation (the shortest route) in radians.
[[nodiscard]] float AngleBetween(const Quaternion& target) const;
/// Returns the axis of rotation to get from this orientation to target orientation (the shortest route).
[[nodiscard]] Vector3 AxisFromTo(const Quaternion& target) const;
[[nodiscard]] AxisAngle ToAxisAngle() const;
void SetFromAxisAngle(const AxisAngle& axisAngle);
/// Sets this quaternion to represent the same rotation as the given matrix.
void Set(const Matrix3x3& matrix);
void Set(const Matrix4x4& matrix);
void Set(float x, float y, float z, float w);
void Set(const Quaternion& q);
void Set(const Vector4& v);
/// Sets this quaternion to represent the same rotation as the given matrix.
void Set(const Matrix3x3& matrix);
void Set(const Matrix4x4& matrix);
void Set(float x, float y, float z, float w);
void Set(const Quaternion& q);
void Set(const Vector4& v);
public:
float x;
float y;
float z;
float w;
};
}
};

View File

@@ -15,11 +15,12 @@ namespace J3ML::LinearAlgebra {
};
}
AxisAngle::AxisAngle(const Quaternion &q) {
auto theta = std::acos(q.w) * 2.f;
auto ax = q.x / std::sin(std::acos(theta));
auto ay = q.y / std::sin(std::acos(theta));
auto az = q.z / std::sin(std::acos(theta));
AxisAngle::AxisAngle(const Quaternion& rhs) {
float halfAngle = std::acos(rhs.w);
angle = halfAngle * 2.f;
float reciprocalSinAngle = 1.f / std::sqrt(1.f - rhs.w*rhs.w);
axis = { rhs.x*reciprocalSinAngle, rhs.y*reciprocalSinAngle, rhs.z*reciprocalSinAngle };
}
EulerAngleXYZ AxisAngle::ToEulerAngleXYZ() const {

View File

@@ -11,8 +11,7 @@ namespace J3ML::LinearAlgebra {
const Quaternion Quaternion::Identity = Quaternion(0.f, 0.f, 0.f, 1.f);
const Quaternion Quaternion::NaN = Quaternion(NAN, NAN, NAN, NAN);
Quaternion Quaternion::operator-() const
{
Quaternion Quaternion::operator-() const {
return {-x, -y, -z, -w};
}
@@ -51,22 +50,6 @@ namespace J3ML::LinearAlgebra {
return (*this * (t - 1.f) + b * t).Normalized();
}
void Quaternion::SetFromAxisAngle(const Vector3 &axis, float angle) {
float sinz, cosz;
sinz = std::sin(angle*0.5f);
cosz = std::cos(angle*0.5f);
x = axis.x * sinz;
y = axis.y * sinz;
z = axis.z * sinz;
w = cosz;
}
void Quaternion::SetFromAxisAngle(const Vector4 &axis, float angle)
{
SetFromAxisAngle(Vector3(axis.x, axis.y, axis.z), angle);
}
Quaternion Quaternion::operator*(float scalar) const {
return Quaternion(x * scalar, y * scalar, z * scalar, w * scalar);
}
@@ -83,8 +66,6 @@ namespace J3ML::LinearAlgebra {
Quaternion Quaternion::operator+() const { return *this; }
Quaternion::Quaternion() {}
Quaternion::Quaternion(float X, float Y, float Z, float W) : x(X), y(Y), z(Z), w(W) {}
// TODO: implement
@@ -149,20 +130,6 @@ namespace J3ML::LinearAlgebra {
return (*this * (a * sign) + q2 * b).Normalized();
}
AxisAngle Quaternion::ToAxisAngle() const {
float halfAngle = std::acos(w);
float angle = halfAngle * 2.f;
// TODO: Can Implement Fast Inverted Sqrt Here
float reciprocalSinAngle = 1.f / std::sqrt(1.f - w*w);
Vector3 axis = {
x*reciprocalSinAngle,
y*reciprocalSinAngle,
z*reciprocalSinAngle
};
return AxisAngle(axis, angle);
}
float Quaternion::AngleBetween(const Quaternion &target) const {
Quaternion delta = target / *this;
return delta.Normalized().Angle();
@@ -213,23 +180,7 @@ namespace J3ML::LinearAlgebra {
return Vector3(x, y, z) * rcpSinAngle;
}
Quaternion::Quaternion(const Vector3 &rotationAxis, float rotationAngleRadians) {
SetFromAxisAngle(rotationAxis, rotationAngleRadians);
}
Quaternion::Quaternion(const Vector4 &rotationAxis, float rotationAngleRadians) {
SetFromAxisAngle(rotationAxis, rotationAngleRadians);
}
Quaternion::Quaternion(const AxisAngle &angle) {
double s = std::sin(angle.angle / 2);
x = angle.axis.x * s;
y = angle.axis.y * s;
z = angle.axis.z * s;
w = std::cos(angle.angle / 2);
}
void Quaternion::SetFrom(const AxisAngle &angle) {
Quaternion::Quaternion(const AxisAngle& angle) {
double s = std::sin(angle.angle / 2);
x = angle.axis.x * s;
y = angle.axis.y * s;
@@ -253,16 +204,16 @@ namespace J3ML::LinearAlgebra {
return Quaternion::Identity;
}
float Quaternion::Normalize() {
bool Quaternion::Normalize() {
float length = Length();
if (length < 1e-4f)
return 0.f;
return false;
float rcpLength = 1.f / length;
x *= rcpLength;
y *= rcpLength;
z *= rcpLength;
w *= rcpLength;
return length;
return true;
}
bool Quaternion::IsNormalized(float epsilon) const {
@@ -310,6 +261,7 @@ namespace J3ML::LinearAlgebra {
return Matrix3x3::LookAt(localForward, targetDirection, localUp, worldUp).ToQuat();
}
/*
Quaternion Quaternion::RotateX(float angleRadians) {
return {{1,0,0}, angleRadians};
}
@@ -325,6 +277,7 @@ namespace J3ML::LinearAlgebra {
Quaternion Quaternion::RotateAxisAngle(const AxisAngle &axisAngle) {
return {axisAngle.axis, axisAngle.angle};
}
*/
Quaternion Quaternion::RotateFromTo(const Vector3 &sourceDirection, const Vector3 &targetDirection) {
assert(sourceDirection.IsNormalized());
@@ -351,14 +304,6 @@ namespace J3ML::LinearAlgebra {
return Quaternion::RotateFromTo(sourceDirection.XYZ(), targetDirection.XYZ());
}
Quaternion::Quaternion(const float *data) {
assert(data);
x = data[0];
y = data[1];
z = data[2];
w = data[3];
}
Quaternion Quaternion::Lerp(const Quaternion &source, const Quaternion &target, float t) { return source.Lerp(target, t);}
Quaternion Quaternion::Slerp(const Quaternion &source, const Quaternion &target, float t) { return source.Slerp(target, t);}
@@ -399,4 +344,11 @@ namespace J3ML::LinearAlgebra {
z = cos_roll * cos_pitch * sin_yaw + sin_roll * sin_pitch * cos_yaw;
w = -sin_roll * sin_pitch * sin_yaw + cos_roll * cos_pitch * cos_yaw;
}
Quaternion::Quaternion(const Quaternion& rhs) {
x = rhs.x;
y = rhs.y;
z = rhs.z;
w = rhs.w;
}
}

View File

@@ -7,8 +7,16 @@ namespace AxisAngleTests {
inline void Define() {
using namespace jtest;
AxisAngleUnit += Test("Not Implemented", [] {
throw("Not Implemented");
AxisAngleUnit += Test("From_Quaternion", [] {
AxisAngle expected_result({0.3860166, 0.4380138, 0.8118714}, 0.6742209);
Quaternion q(0.1276794, 0.1448781, 0.2685358, 0.9437144);
AxisAngle from_quaternion(q);
jtest::check(Math::EqualAbs(expected_result.axis.x, from_quaternion.axis.x, 1e-6f));
jtest::check(Math::EqualAbs(expected_result.axis.y, from_quaternion.axis.y, 1e-6f));
jtest::check(Math::EqualAbs(expected_result.axis.z, from_quaternion.axis.z, 1e-6f));
jtest::check(Math::EqualAbs(expected_result.angle, from_quaternion.angle, 1e-6f));
});
}
inline void Run() {

View File

@@ -9,6 +9,9 @@
jtest::Unit QuaternionUnit {"Quaternion"};
namespace QuaternionTests {
// This is here to check the accuracy of the Slerp inside the Quaternion class.
// Although you don't jtest::check anything :shrug: - Redacted.
Quaternion PreciseSlerp(const Quaternion &a, const Quaternion& b, float t)
{
double angle = a.x * b.x + a.y * b.y + a.z * b.z + a.w * b.w;
@@ -80,6 +83,18 @@ namespace QuaternionTests {
jtest::check(Math::EqualAbs(expected_result.z, from_euler.z, 1e-6f));
jtest::check(Math::EqualAbs(expected_result.w, from_euler.w, 1e-6f));
});
QuaternionUnit += Test("From_AxisAngle", [] {
Quaternion expected_result(0.0579133, 0.0782044, 0.1765667, 0.9794664);
AxisAngle a({0.2872573, 0.3879036, 0.8757934}, 0.4059981);
Quaternion from_axis(a);
jtest::check(Math::EqualAbs(expected_result.x, from_axis.x, 1e-6f));
jtest::check(Math::EqualAbs(expected_result.y, from_axis.y, 1e-6f));
jtest::check(Math::EqualAbs(expected_result.z, from_axis.z, 1e-6f));
jtest::check(Math::EqualAbs(expected_result.w, from_axis.w, 1e-6f));
});
QuaternionUnit += Test("Mat4x4Conversion", [] { throw("Not Implemented"); });
QuaternionUnit += Test("MulOpQuat", [] { throw("Not Implemented"); });
QuaternionUnit += Test("DivOpQuat", [] { throw("Not Implemented"); });