Răsfoiți Sursa

Made ConvexVsMesh performance test 5% faster

* Changed the early out condition for the validity of the contact cache to do a cheap check before a more expensive check. 
* Removed a division and remainder operation from the FixedSizeFreeList, this was taking 13% of the tree walk in QuadTree::FindCollidingPairs, now around 1%
* Added a number of helper functions + unit tests to Quat
Jorrit Rouwe 3 ani în urmă
părinte
comite
377931cd27

+ 8 - 2
Jolt/Core/FixedSizeFreeList.h

@@ -35,8 +35,8 @@ private:
 	static_assert(alignof(ObjectStorage) == alignof(Object), "Object not properly aligned");
 
 	/// Access the object storage given the object index
-	const ObjectStorage &	GetStorage(uint32 inObjectIndex) const	{ return mPages[inObjectIndex / mPageSize][inObjectIndex % mPageSize]; }
-	ObjectStorage &			GetStorage(uint32 inObjectIndex)		{ return mPages[inObjectIndex / mPageSize][inObjectIndex % mPageSize]; }
+	const ObjectStorage &	GetStorage(uint32 inObjectIndex) const	{ return mPages[inObjectIndex >> mPageShift][inObjectIndex & mObjectMask]; }
+	ObjectStorage &			GetStorage(uint32 inObjectIndex)		{ return mPages[inObjectIndex >> mPageShift][inObjectIndex & mObjectMask]; }
 
 	/// Number of objects that we currently have in the free list / new pages
 #ifdef JPH_ENABLE_ASSERTS
@@ -52,6 +52,12 @@ private:
 	/// Size (in objects) of a single page
 	uint32					mPageSize;
 
+	/// Number of bits to shift an object index to the right to get the page number
+	uint32					mPageShift;
+
+	/// Mask to and an object index with to get the page number
+	uint32					mObjectMask;
+
 	/// Total number of pages that are usable
 	uint32					mNumPages;
 

+ 3 - 0
Jolt/Core/FixedSizeFreeList.inl

@@ -20,11 +20,14 @@ template <typename Object>
 void FixedSizeFreeList<Object>::Init(uint inMaxObjects, uint inPageSize)
 {
 	// Check sanity
+	JPH_ASSERT(inPageSize > 0 && IsPowerOf2(inPageSize));
 	JPH_ASSERT(mPages == nullptr);
 
 	// Store configuration parameters
 	mNumPages = (inMaxObjects + inPageSize - 1) / inPageSize;
 	mPageSize = inPageSize;
+	mPageShift = CountTrailingZeros(inPageSize);
+	mObjectMask = inPageSize - 1;
 	JPH_IF_ENABLE_ASSERTS(mNumFreeObjects = mNumPages * inPageSize;)
 
 	// Allocate page table

+ 22 - 19
Jolt/Math/Quat.h

@@ -123,7 +123,7 @@ public:
 	JPH_INLINE float			Length() const													{ return mValue.Length(); }	
 
 	/// Normalize the quaternion (make it length 1)
-	JPH_INLINE const Quat		Normalized() const												{ return Quat(mValue.Normalized()); }
+	JPH_INLINE Quat				Normalized() const												{ return Quat(mValue.Normalized()); }
 
 	///@}
 	///@name Additions / multiplications
@@ -133,42 +133,45 @@ public:
 	JPH_INLINE void				operator -= (QuatArg inRHS)										{ mValue -= inRHS.mValue; }
 	JPH_INLINE void				operator *= (float inValue)										{ mValue *= inValue; }
 	JPH_INLINE void				operator /= (float inValue)										{ mValue /= inValue; }
-	JPH_INLINE const Quat		operator - () const												{ return Quat(-mValue); }
-	JPH_INLINE const Quat		operator + (QuatArg inRHS) const								{ return Quat(mValue + inRHS.mValue); }
-	JPH_INLINE const Quat		operator - (QuatArg inRHS) const								{ return Quat(mValue - inRHS.mValue); }
-	JPH_INLINE const Quat		operator * (QuatArg inRHS) const;
-	JPH_INLINE const Quat		operator * (float inValue) const								{ return Quat(mValue * inValue); }
-	inline friend const Quat	operator * (float inValue, QuatArg inRHS)						{ return Quat(inRHS.mValue * inValue); }
-	JPH_INLINE const Quat		operator / (float inValue) const								{ return Quat(mValue / inValue); }
+	JPH_INLINE Quat				operator - () const												{ return Quat(-mValue); }
+	JPH_INLINE Quat				operator + (QuatArg inRHS) const								{ return Quat(mValue + inRHS.mValue); }
+	JPH_INLINE Quat				operator - (QuatArg inRHS) const								{ return Quat(mValue - inRHS.mValue); }
+	JPH_INLINE Quat				operator * (QuatArg inRHS) const;
+	JPH_INLINE Quat				operator * (float inValue) const								{ return Quat(mValue * inValue); }
+	inline friend Quat			operator * (float inValue, QuatArg inRHS)						{ return Quat(inRHS.mValue * inValue); }
+	JPH_INLINE Quat				operator / (float inValue) const								{ return Quat(mValue / inValue); }
 
 	///@}
 
 	/// Rotate a vector by this quaternion 
-	JPH_INLINE const Vec3		operator * (Vec3Arg inValue) const;
+	JPH_INLINE Vec3				operator * (Vec3Arg inValue) const;
 
 	/// Rotate a vector by the inverse of this quaternion
-	JPH_INLINE const Vec3		InverseRotate(Vec3Arg inValue) const;
+	JPH_INLINE Vec3				InverseRotate(Vec3Arg inValue) const;
 
 	/// Rotate a the vector (1, 0, 0) with this quaternion
-	JPH_INLINE const Vec3		RotateAxisX() const;
+	JPH_INLINE Vec3				RotateAxisX() const;
 								
 	/// Rotate a the vector (0, 1, 0) with this quaternion
-	JPH_INLINE const Vec3		RotateAxisY() const;
+	JPH_INLINE Vec3				RotateAxisY() const;
 								
 	/// Rotate a the vector (0, 0, 1) with this quaternion
-	JPH_INLINE const Vec3		RotateAxisZ() const;
+	JPH_INLINE Vec3				RotateAxisZ() const;
 								
 	/// Dot product				
 	JPH_INLINE float			Dot(QuatArg inRHS) const										{ return mValue.Dot(inRHS.mValue); }
 								
 	/// The conjugate [w, -x, -y, -z] is the same as the inverse for unit quaternions
-	JPH_INLINE const Quat		Conjugated() const												{ return Quat(Vec4(-1, -1, -1, 1) * mValue); }
+	JPH_INLINE Quat				Conjugated() const												{ return Quat(Vec4::sXor(mValue, UVec4(0x80000000, 0x80000000, 0x80000000, 0).ReinterpretAsFloat())); }
 
 	/// Get inverse quaternion
-	JPH_INLINE const Quat		Inversed() const												{ return Conjugated() / Length(); }
+	JPH_INLINE Quat				Inversed() const												{ return Conjugated() / Length(); }
+
+	/// Ensures that the W component is positive by negating the entire quaternion if it is not. This is useful when you want to store a quaternion as a 3 vector by discarding W and reconstructing it as sqrt(1 - x^2 - y^2 - z^2).
+	JPH_INLINE Quat				EnsureWPositive() const											{ return Quat(Vec4::sXor(mValue, Vec4::sAnd(mValue.SplatW(), UVec4::sReplicate(0x80000000).ReinterpretAsFloat()))); }
 
 	/// Get a quaternion that is perpendicular to this quaternion
-	JPH_INLINE const Quat		GetPerpendicular() const										{ return Quat(Vec4(1, -1, 1, -1) * mValue.Swizzle<SWIZZLE_Y, SWIZZLE_X, SWIZZLE_W, SWIZZLE_Z>()); }
+	JPH_INLINE Quat				GetPerpendicular() const										{ return Quat(Vec4(1, -1, 1, -1) * mValue.Swizzle<SWIZZLE_Y, SWIZZLE_X, SWIZZLE_W, SWIZZLE_Z>()); }
 
 	/// Get rotation angle around inAxis (uses Swing Twist Decomposition to get the twist quaternion and uses q(axis, angle) = [cos(angle / 2), axis * sin(angle / 2)])
 	JPH_INLINE float			GetRotationAngle(Vec3Arg inAxis) const							{ return GetW() == 0.0f? JPH_PI : 2.0f * atan(GetXYZ().Dot(inAxis) / GetW()); }
@@ -190,7 +193,7 @@ public:
 	/// \f[q_{swing} = q \: q_{twist}^* \f]
 	///
 	/// Where \f$q_{twist}^*\f$ = complex conjugate of \f$q_{twist}\f$
-	JPH_INLINE const Quat		GetTwist(Vec3Arg inAxis) const;
+	JPH_INLINE Quat				GetTwist(Vec3Arg inAxis) const;
 
 	/// Decomposes quaternion into swing and twist component:
 	///
@@ -210,14 +213,14 @@ public:
 	/// @param inFraction is in the range [0, 1]
 	/// @param inDestination The destination quaternion
 	/// @return (1 - inFraction) * this + fraction * inDestination
-	JPH_INLINE const Quat		LERP(QuatArg inDestination, float inFraction) const;
+	JPH_INLINE Quat				LERP(QuatArg inDestination, float inFraction) const;
 
 	/// Spherical linear interpolation between two quaternions.
 	/// @param inFraction is in the range [0, 1]
 	/// @param inDestination The destination quaternion
 	/// @return When fraction is zero this quaternion is returned, when fraction is 1 inDestination is returned. 
 	/// When fraction is between 0 and 1 an interpolation along the shortest path is returned.
-	JPH_INLINE const Quat		SLERP(QuatArg inDestination, float inFraction) const;
+	JPH_INLINE Quat				SLERP(QuatArg inDestination, float inFraction) const;
 	
 	/// Load 3 floats from memory (X, Y and Z component and then calculates W) reads 32 bits extra which it doesn't use
 	static JPH_INLINE Quat		sLoadFloat3Unsafe(const Float3 &inV);

+ 13 - 14
Jolt/Math/Quat.inl

@@ -3,7 +3,7 @@
 
 namespace JPH {
 
-const Quat Quat::operator * (QuatArg inRHS) const
+Quat Quat::operator * (QuatArg inRHS) const
 { 
 #if defined(JPH_USE_SSE)
 	// Taken from: http://momchil-velikov.blogspot.nl/2013/10/fast-sse-quternion-multiplication.html
@@ -80,8 +80,8 @@ Quat Quat::sRotation(Vec3Arg inAxis, float inAngle)
 void Quat::GetAxisAngle(Vec3 &outAxis, float &outAngle) const
 {
 	JPH_ASSERT(IsNormalized());
-	float w = GetW();
-	float abs_w = abs(w);
+	Quat w_pos = EnsureWPositive();
+	float abs_w = w_pos.GetW();
 	if (abs_w >= 1.0f)
 	{ 
 		outAxis = Vec3::sZero();
@@ -90,8 +90,7 @@ void Quat::GetAxisAngle(Vec3 &outAxis, float &outAngle) const
 	else
 	{
 		outAngle = 2.0f * acos(abs_w);
-		float len = GetXYZ().Length();
-		outAxis = len > 0.0f? (w < 0.0f? -GetXYZ() : GetXYZ()) / len : Vec3::sZero();
+		outAxis = w_pos.GetXYZ().NormalizedOr(Vec3::sZero());
 	}
 }
 
@@ -189,7 +188,7 @@ Vec3 Quat::GetEulerAngles() const
 	return Vec3(atan2(t0, t1), asin(t2), atan2(t3, t4));
 }
 
-const Quat Quat::GetTwist(Vec3Arg inAxis) const
+Quat Quat::GetTwist(Vec3Arg inAxis) const
 { 
 	Quat twist(Vec4(GetXYZ().Dot(inAxis) * inAxis, GetW()));
 	float twist_len = twist.LengthSq();
@@ -216,13 +215,13 @@ void Quat::GetSwingTwist(Quat &outSwing, Quat &outTwist) const
 	}
 }
 
-const Quat Quat::LERP(QuatArg inDestination, float inFraction) const
+Quat Quat::LERP(QuatArg inDestination, float inFraction) const
 {
 	float scale0 = 1.0f - inFraction;
 	return Quat(Vec4::sReplicate(scale0) * mValue + Vec4::sReplicate(inFraction) * inDestination.mValue);
 }
 
-const Quat Quat::SLERP(QuatArg inDestination, float inFraction) const
+Quat Quat::SLERP(QuatArg inDestination, float inFraction) const
 {	
     // Difference at which to LERP instead of SLERP
 	const float delta = 0.0001f;
@@ -259,20 +258,20 @@ const Quat Quat::SLERP(QuatArg inDestination, float inFraction) const
 	return Quat(Vec4::sReplicate(scale0) * mValue + Vec4::sReplicate(scale1) * inDestination.mValue).Normalized();
 }
 
-const Vec3 Quat::operator * (Vec3Arg inValue) const
+Vec3 Quat::operator * (Vec3Arg inValue) const
 {
 	// Rotating a vector by a quaternion is done by: p' = q * p * q^-1 (q^-1 = conjugated(q) for a unit quaternion)
 	JPH_ASSERT(IsNormalized());
 	return Vec3((*this * Quat(Vec4(inValue, 0)) * Conjugated()).mValue);
 }
 
-const Vec3 Quat::InverseRotate(Vec3Arg inValue) const
+Vec3 Quat::InverseRotate(Vec3Arg inValue) const
 {
 	JPH_ASSERT(IsNormalized());
 	return Vec3((Conjugated() * Quat(Vec4(inValue, 0)) * *this).mValue);
 }
 
-const Vec3 Quat::RotateAxisX() const												
+Vec3 Quat::RotateAxisX() const												
 { 
 	// This is *this * Vec3::sAxisX() written out:
 	JPH_ASSERT(IsNormalized());
@@ -281,7 +280,7 @@ const Vec3 Quat::RotateAxisX() const
 	return Vec3(tx * x + tw * w - 1.0f, tx * y + z * tw, tx * z - y * tw); 
 }
 
-const Vec3 Quat::RotateAxisY() const												
+Vec3 Quat::RotateAxisY() const												
 { 
 	// This is *this * Vec3::sAxisY() written out:
 	JPH_ASSERT(IsNormalized());
@@ -290,7 +289,7 @@ const Vec3 Quat::RotateAxisY() const
 	return Vec3(x * ty - z * tw, tw * w + ty * y - 1.0f, x * tw + ty * z); 
 }
 
-const Vec3 Quat::RotateAxisZ() const												
+Vec3 Quat::RotateAxisZ() const												
 { 
 	// This is *this * Vec3::sAxisZ() written out:
 	JPH_ASSERT(IsNormalized());
@@ -302,7 +301,7 @@ const Vec3 Quat::RotateAxisZ() const
 void Quat::StoreFloat3(Float3 *outV) const
 {
 	JPH_ASSERT(IsNormalized());
-	Vec3(GetW() < 0.0f? -mValue : mValue).StoreFloat3(outV);
+	EnsureWPositive().GetXYZ().StoreFloat3(outV);
 }
 
 Quat Quat::sLoadFloat3Unsafe(const Float3 &inV)

+ 3 - 0
Jolt/Math/Vec4.h

@@ -229,6 +229,9 @@ public:
 	/// Component wise square root
 	JPH_INLINE Vec4				Sqrt() const;
 
+	/// Get vector that contains the sign of each element (returns 1.0f if positive, -1.0f if negative)
+	JPH_INLINE Vec4				GetSign() const;
+
 	/// To String
 	friend ostream &			operator << (ostream &inStream, Vec4Arg inV)
 	{

+ 16 - 0
Jolt/Math/Vec4.inl

@@ -608,6 +608,22 @@ Vec4 Vec4::Sqrt() const
 #endif
 }
 
+
+Vec4 Vec4::GetSign() const
+{
+#if defined(JPH_USE_SSE)
+	Type minus_one = _mm_set1_ps(-1.0f);
+	Type one = _mm_set1_ps(1.0f);
+	return _mm_or_ps(_mm_and_ps(mValue, minus_one), one);
+#elif defined(JPH_USE_NEON)
+	Type minus_one = vdupq_n_f32(-1.0f);
+	Type one = vdupq_n_f32(1.0f);
+	return vorrq_s32(vandq_s32(mValue, minus_one), one);
+#else
+	#error Unsupported CPU architecture
+#endif
+}
+
 Vec4 Vec4::Normalized() const
 {
 #if defined(JPH_USE_SSE)

+ 24 - 30
Jolt/Physics/Constraints/ContactConstraintManager.cpp

@@ -596,22 +596,6 @@ void ContactConstraintManager::PrepareConstraintBuffer(PhysicsUpdateContext *inC
 	mConstraints = (ContactConstraint *)inContext->mTempAllocator->Allocate(mMaxConstraints * sizeof(ContactConstraint));
 }
 
-// Get the orientation of body 2 in local space of body 1
-static JPH_INLINE void sGetRelativeOrientation(const Body &inBody1, const Body &inBody2, Vec3 &outDeltaPosition, Quat &outDeltaRotation)
-{
-	Quat inv_r1 = inBody1.GetRotation().Conjugated();
-
-	// Get relative rotation
-	outDeltaRotation = inv_r1 * inBody2.GetRotation();
-
-	// Ensure W > 0, we'll be discarding it to save storage space
-	if (outDeltaRotation.GetW() < 0.0f)
-		outDeltaRotation = -outDeltaRotation;
-
-	// Get relative translation
-	outDeltaPosition = inv_r1 * (inBody2.GetCenterOfMassPosition() - inBody1.GetCenterOfMassPosition());
-}
-
 void ContactConstraintManager::GetContactsFromCache(ContactAllocator &ioContactAllocator, Body &inBody1, Body &inBody2, bool &outPairHandled, bool &outContactFound)
 {
 	JPH_PROFILE_FUNCTION();
@@ -642,22 +626,28 @@ void ContactConstraintManager::GetContactsFromCache(ContactAllocator &ioContactA
 		return;
 	const CachedBodyPair &input_cbp = kv->GetValue();
 
+	// Get relative translation
+	Quat inv_r1 = body1->GetRotation().Conjugated();
+	Vec3 delta_position = inv_r1 * (body2->GetCenterOfMassPosition() - body1->GetCenterOfMassPosition());
+
 	// Get old position delta
 	Vec3 old_delta_position = Vec3::sLoadFloat3Unsafe(input_cbp.mDeltaPosition);
 
-	// Reconstruct old quaternion delta
-	Vec3 old_delta_rotation3 = Vec3::sLoadFloat3Unsafe(input_cbp.mDeltaRotation);
-	Quat old_delta_rotation(Vec4(old_delta_rotation3, sqrt(max(0.0f, 1.0f - old_delta_rotation3.LengthSq()))));
+	// Check if bodies are still roughly in the same relative position
+	if ((delta_position - old_delta_position).LengthSq() > mPhysicsSettings.mBodyPairCacheMaxDeltaPositionSq)
+		return;
 
 	// Determine relative orientation
-	Vec3 delta_position;
-	Quat delta_rotation;
-	sGetRelativeOrientation(*body1, *body2, delta_position, delta_rotation);
+	Quat delta_rotation = inv_r1 * body2->GetRotation();
+
+	// Reconstruct old quaternion delta
+	Quat old_delta_rotation = Quat::sLoadFloat3Unsafe(input_cbp.mDeltaRotation);
 
 	// Check if bodies are still roughly in the same relative orientation
-	if ((delta_position - old_delta_position).LengthSq() > mPhysicsSettings.mBodyPairCacheMaxDeltaPositionSq)
-		return;
-	if (delta_rotation.Dot(old_delta_rotation) < mPhysicsSettings.mBodyPairCacheCosMaxDeltaRotation)
+	// The delta between 2 quaternions p and q is: p q^* = [rotation_axis * sin(angle / 2), cos(angle / 2)]
+	// From the W component we can extract the angle: cos(angle / 2) = px * qx + py * qy + pz * qz + pw * qw = p . q
+	// Since we want to abort if the rotation is smaller than -angle or bigger than angle, we can write the comparison as |p . q| < cos(angle / 2)
+	if (abs(delta_rotation.Dot(old_delta_rotation)) < mPhysicsSettings.mBodyPairCacheCosMaxDeltaRotationDiv2)
 		return;
 
 	// The cache is valid, return that we've handled this body pair
@@ -830,14 +820,18 @@ ContactConstraintManager::BodyPairHandle ContactConstraintManager::AddBodyPair(C
 	CachedBodyPair *cbp = &body_pair_kv->GetValue();
 	cbp->mFirstCachedManifold = ManifoldMap::cInvalidHandle;
 
-	// Determine relative orientation
-	Vec3 delta_position;
-	Quat delta_rotation;
-	sGetRelativeOrientation(*body1, *body2, delta_position, delta_rotation);
+	// Get relative translation
+	Quat inv_r1 = body1->GetRotation().Conjugated();
+	Vec3 delta_position = inv_r1 * (body2->GetCenterOfMassPosition() - body1->GetCenterOfMassPosition());
 
 	// Store it
 	delta_position.StoreFloat3(&cbp->mDeltaPosition);
-	delta_rotation.GetXYZ().StoreFloat3(&cbp->mDeltaRotation);
+
+	// Determine relative orientation
+	Quat delta_rotation = inv_r1 * body2->GetRotation();
+
+	// Store it
+	delta_rotation.StoreFloat3(&cbp->mDeltaRotation);
 
 	return cbp;
 }

+ 2 - 2
Jolt/Physics/PhysicsSettings.h

@@ -61,8 +61,8 @@ struct PhysicsSettings
 	/// Maximum relative delta position for body pairs to be able to reuse collision results from last frame (units: meter^2)
 	float		mBodyPairCacheMaxDeltaPositionSq = Square(0.001f); ///< 1 mm
 
-	/// Maximum relative delta orientation for body pairs to be able to reuse collision results from last frame
-	float		mBodyPairCacheCosMaxDeltaRotation = 0.99984769515639123915701155881391f; ///< cos(1 degree)
+	/// Maximum relative delta orientation for body pairs to be able to reuse collision results from last frame, stored as cos(max angle / 2)
+	float		mBodyPairCacheCosMaxDeltaRotationDiv2 = 0.99984769515639123915701155881391f; ///< cos(2 degrees / 2)
 
 	/// Maximum angle between normals that allows manifolds between different sub shapes of the same body pair to be combined
 	float		mContactNormalCosMaxDeltaRotation = 0.99619469809174553229501040247389f; ///< cos(5 degree)

+ 2 - 2
UnitTests/Core/JobSystemTest.cpp

@@ -9,7 +9,7 @@ TEST_SUITE("JobSystemTest")
 	TEST_CASE("TestJobSystemRunJobs")
 	{
 		// Create job system
-		const int cMaxJobs = 100;
+		const int cMaxJobs = 128;
 		const int cMaxBarriers = 10;
 		const int cMaxThreads = 10;
 		JobSystemThreadPool system(cMaxJobs, cMaxBarriers, cMaxThreads);
@@ -43,7 +43,7 @@ TEST_SUITE("JobSystemTest")
 	TEST_CASE("TestJobSystemRunChain")
 	{
 		// Create job system
-		const int cMaxJobs = 100;
+		const int cMaxJobs = 128;
 		const int cMaxBarriers = 10;
 		JobSystemThreadPool system(cMaxJobs, cMaxBarriers);
 

+ 82 - 0
UnitTests/Math/QuatTests.cpp

@@ -8,6 +8,21 @@
 
 TEST_SUITE("QuatTests")
 {
+	TEST_CASE("TestQuatEqual")
+	{
+		CHECK(Quat(1, 2, 3, 4) == Quat(1, 2, 3, 4));
+		CHECK(Quat(1, 2, 3, 4) != Quat(0, 2, 3, 4));
+		CHECK(Quat(1, 2, 3, 4) != Quat(1, 0, 3, 4));
+		CHECK(Quat(1, 2, 3, 4) != Quat(1, 2, 0, 4));
+		CHECK(Quat(1, 2, 3, 4) != Quat(1, 2, 3, 0));
+	}
+
+	TEST_CASE("TestQuatZero")
+	{
+		Quat zero = Quat::sZero();
+		CHECK(zero == Quat(0, 0, 0, 0));
+	}
+
 	TEST_CASE("TestQuatIdentity")
 	{
 		Quat identity = Quat::sIdentity();
@@ -18,6 +33,45 @@ TEST_SUITE("QuatTests")
 		CHECK_APPROX_EQUAL(identity.GetW(), 1.0f);
 	}
 
+	TEST_CASE("TestQuatIsNaN")
+	{
+		CHECK(Quat(numeric_limits<float>::quiet_NaN(), 0, 0, 0).IsNaN());
+		CHECK(Quat(0, numeric_limits<float>::quiet_NaN(), 0, 0).IsNaN());
+		CHECK(Quat(0, 0, numeric_limits<float>::quiet_NaN(), 0).IsNaN());
+		CHECK(Quat(0, 0, 0, numeric_limits<float>::quiet_NaN()).IsNaN());
+	}
+	
+	TEST_CASE("TestQuatOperators")
+	{
+		CHECK(-Quat(1, 2, 3, 4) == Quat(-1, -2, -3, -4));
+		CHECK(Quat(1, 2, 3, 4) + Quat(5, 6, 7, 8) == Quat(6, 8, 10, 12));
+		CHECK(Quat(5, 6, 7, 8) - Quat(4, 3, 2, 1) == Quat(1, 3, 5, 7));
+		CHECK(Quat(1, 2, 3, 4) * 5.0f == Quat(5, 10, 15, 20));
+		CHECK(5.0f * Quat(1, 2, 3, 4) == Quat(5, 10, 15, 20));
+		CHECK(Quat(2, 4, 6, 8) / 2.0f == Quat(1, 2, 3, 4));
+	}
+
+	TEST_CASE("TestQuatPerpendicular")
+	{
+		Quat q1(1, 2, 3, 4);
+		CHECK(q1.GetPerpendicular().Dot(q1) == 0.0f);
+
+		Quat q2(-5, 4, -3, 2);
+		CHECK(q2.GetPerpendicular().Dot(q2) == 0.0f);
+	}
+
+	TEST_CASE("TestQuatNormalized")
+	{
+		CHECK(Quat(1, 0, 0, 0).IsNormalized());
+		CHECK(Quat(-0.7071067f, 0.7071067f, 0, 0).IsNormalized());
+		CHECK(Quat(0.5773502f, -0.5773502f, 0.5773502f, 0).IsNormalized());
+		CHECK(Quat(0.5f, -0.5f, 0.5f, -0.5f).IsNormalized());
+		CHECK(!Quat(2, 0, 0, 0).IsNormalized());
+		CHECK(!Quat(0, 2, 0, 0).IsNormalized());
+		CHECK(!Quat(0, 0, 2, 0).IsNormalized());
+		CHECK(!Quat(0, 0, 0, 2).IsNormalized());
+	}
+
 	TEST_CASE("TestQuatConvertMatrix")
 	{
 		UnitTestRandom random;
@@ -231,6 +285,34 @@ TEST_SUITE("QuatTests")
 		}
 	}
 
+	TEST_CASE("TestQuatConjugate")
+	{
+		CHECK(Quat(1, 2, 3, 4).Conjugated() == Quat(-1, -2, -3, 4));
+		CHECK(Quat(-1, -2, -3, -4).Conjugated() == Quat(1, 2, 3, -4));
+	}
+
+	TEST_CASE("TestQuatEnsureWPositive")
+	{
+		CHECK(Quat(1, -2, 3, -4).EnsureWPositive() == Quat(-1, 2, -3, 4));
+		CHECK(Quat(-4, 5, -6, 7).EnsureWPositive() == Quat(-4, 5, -6, 7));
+		CHECK(Quat(1, 2, 3, 0).EnsureWPositive() == Quat(1, 2, 3, 0));
+	}
+
+	TEST_CASE("TestQuatStoreFloat3")
+	{
+		Float3 q1;
+		Quat(0.7071067f, 0, 0, -0.7071067f).StoreFloat3(&q1);
+		CHECK(q1 == Float3(-0.7071067f, 0, 0));
+
+		Float3 q2;
+		Quat(0, 0.7071067f, 0, 0.7071067f).StoreFloat3(&q2);
+		CHECK(q2 == Float3(0, 0.7071067f, 0));
+
+		Float3 q3;
+		Quat(0, 0, 1, 0).StoreFloat3(&q3);
+		CHECK(q3 == Float3(0, 0, 1));
+	}
+
 	TEST_CASE("TestQuatGetTwistAxis")
 	{
 		Quat q1 = Quat::sRotation(Vec3::sAxisX(), DegreesToRadians(-10.0f));

+ 6 - 0
UnitTests/Math/Vec4Tests.cpp

@@ -470,6 +470,12 @@ TEST_SUITE("Vec4Tests")
 		CHECK(Vec4(1, 2, 3, 4).ReinterpretAsInt() == UVec4(0x3f800000U, 0x40000000U, 0x40400000U, 0x40800000U));
 	}
 
+	TEST_CASE("TestVec4Sign")
+	{
+		CHECK(Vec4(1.2345f, -6.7891f, 0, 1).GetSign() == Vec4(1, -1, 1, 1));
+		CHECK(Vec4(0, 2.3456f, -7.8912f, -1).GetSign() == Vec4(1, 1, -1, -1));
+	}
+
 	TEST_CASE("TestVec4SignBit")
 	{
 		CHECK(Vec4(2, -3, 4, -5).GetSignBits() == 0b1010);