Browse Source

Collision detection optimizations (#36)

* Added specialization for sphere vs triangle, making it about 40% faster (saves about 4% in ConvexVsMesh test)
* Ability to tweak the max triangles per leaf, saves (saves about 2% in ConvexVsMesh test)
* Implemented proper Multiply3x3Transposed function in SSE
Jorrit Rouwe 3 years ago
parent
commit
41471b4016

+ 27 - 8
Jolt/Geometry/AABox4.h

@@ -28,24 +28,24 @@ JPH_INLINE UVec4 AABox4VsBox(const AABox &inBox1, Vec4Arg inBox2MinX, Vec4Arg in
 	return UVec4::sNot(UVec4::sOr(UVec4::sOr(nooverlapx, nooverlapy), nooverlapz));
 }
 
-/// Scale 4 bounding boxes
-JPH_INLINE void AABox4Scale(Vec3Arg inScale, Vec4Arg inBoundsMinX, Vec4Arg inBoundsMinY, Vec4Arg inBoundsMinZ, Vec4Arg inBoundsMaxX, Vec4Arg inBoundsMaxY, Vec4Arg inBoundsMaxZ, Vec4 &outBoundsMinX, Vec4 &outBoundsMinY, Vec4 &outBoundsMinZ, Vec4 &outBoundsMaxX, Vec4 &outBoundsMaxY, Vec4 &outBoundsMaxZ)
+/// Scale 4 axis aligned boxes
+JPH_INLINE void AABox4Scale(Vec3Arg inScale, Vec4Arg inBoxMinX, Vec4Arg inBoxMinY, Vec4Arg inBoxMinZ, Vec4Arg inBoxMaxX, Vec4Arg inBoxMaxY, Vec4Arg inBoxMaxZ, Vec4 &outBoundsMinX, Vec4 &outBoundsMinY, Vec4 &outBoundsMinZ, Vec4 &outBoundsMaxX, Vec4 &outBoundsMaxY, Vec4 &outBoundsMaxZ)
 {
 	Vec4 scale_x = inScale.SplatX();
-	Vec4 scaled_min_x = scale_x * inBoundsMinX;
-	Vec4 scaled_max_x = scale_x * inBoundsMaxX;
+	Vec4 scaled_min_x = scale_x * inBoxMinX;
+	Vec4 scaled_max_x = scale_x * inBoxMaxX;
 	outBoundsMinX = Vec4::sMin(scaled_min_x, scaled_max_x); // Negative scale can flip min and max
 	outBoundsMaxX = Vec4::sMax(scaled_min_x, scaled_max_x);
 
 	Vec4 scale_y = inScale.SplatY();
-	Vec4 scaled_min_y = scale_y * inBoundsMinY;
-	Vec4 scaled_max_y = scale_y * inBoundsMaxY;
+	Vec4 scaled_min_y = scale_y * inBoxMinY;
+	Vec4 scaled_max_y = scale_y * inBoxMaxY;
 	outBoundsMinY = Vec4::sMin(scaled_min_y, scaled_max_y);
 	outBoundsMaxY = Vec4::sMax(scaled_min_y, scaled_max_y);
 
 	Vec4 scale_z = inScale.SplatZ();
-	Vec4 scaled_min_z = scale_z * inBoundsMinZ;
-	Vec4 scaled_max_z = scale_z * inBoundsMaxZ;
+	Vec4 scaled_min_z = scale_z * inBoxMinZ;
+	Vec4 scaled_max_z = scale_z * inBoxMaxZ;
 	outBoundsMinZ = Vec4::sMin(scaled_min_z, scaled_max_z);
 	outBoundsMaxZ = Vec4::sMax(scaled_min_z, scaled_max_z);
 }
@@ -188,4 +188,23 @@ JPH_INLINE UVec4 AABox4VsBox(const OrientedBox &inBox, Vec4Arg inBoxMinX, Vec4Ar
 	return AABox4VsBox(inBox.mOrientation, inBox.mHalfExtents, inBoxMinX, inBoxMinY, inBoxMinZ, inBoxMaxX, inBoxMaxY, inBoxMaxZ, inEpsilon);
 }
 
+/// Test 4 AABoxes vs a sphere
+JPH_INLINE UVec4 AABox4VsSphere(Vec4Arg inCenterX, Vec4Arg inCenterY, Vec4Arg inCenterZ, Vec4Arg inRadiusSq, Vec4Arg inBoxMinX, Vec4Arg inBoxMinY, Vec4Arg inBoxMinZ, Vec4Arg inBoxMaxX, Vec4Arg inBoxMaxY, Vec4Arg inBoxMaxZ)
+{
+	// Get closest point on box
+	Vec4 closest_x = Vec4::sMin(Vec4::sMax(inCenterX, inBoxMinX), inBoxMaxX);
+	Vec4 closest_y = Vec4::sMin(Vec4::sMax(inCenterY, inBoxMinY), inBoxMaxY);
+	Vec4 closest_z = Vec4::sMin(Vec4::sMax(inCenterZ, inBoxMinZ), inBoxMaxZ);
+
+	// Test the distance from the center of the sphere to the box is smaller than the radius
+	Vec4 distance_sq = Square(closest_x - inCenterX) + Square(closest_y - inCenterY) + Square(closest_z - inCenterZ);
+	return Vec4::sLessOrEqual(distance_sq, inRadiusSq);
+}
+
+/// Test 4 AABoxes vs a sphere
+JPH_INLINE UVec4 AABox4VsSphere(Vec3 inCenter, float inRadiusSq, Vec4Arg inBoxMinX, Vec4Arg inBoxMinY, Vec4Arg inBoxMinZ, Vec4Arg inBoxMaxX, Vec4Arg inBoxMaxY, Vec4Arg inBoxMaxZ)
+{
+	return AABox4VsSphere(inCenter.SplatX(), inCenter.SplatY(), inCenter.SplatZ(), Vec4::sReplicate(inRadiusSq), inBoxMinX, inBoxMinY, inBoxMinZ, inBoxMaxX, inBoxMaxY, inBoxMaxZ);
+}
+
 } // JPH

+ 2 - 0
Jolt/Jolt.cmake

@@ -188,6 +188,8 @@ set(JOLT_PHYSICS_SRC_FILES
 	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollideConvexVsTriangles.h
 	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollidePointResult.h
 	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollideShape.h
+	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollideSphereVsTriangles.cpp
+	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollideSphereVsTriangles.h
 	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollisionCollector.h
 	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollisionCollectorImpl.h
 	${JOLT_PHYSICS_ROOT}/Physics/Collision/CollisionDispatch.cpp

+ 9 - 0
Jolt/Math/Mat44.inl

@@ -295,7 +295,16 @@ Vec3 Mat44::Multiply3x3(Vec3Arg inV) const
 
 Vec3 Mat44::Multiply3x3Transposed(Vec3Arg inV) const
 {
+#if defined(JPH_USE_SSE)
+	__m128 x = _mm_dp_ps(mCol[0].mValue, inV.mValue, 0x7f);
+	__m128 y = _mm_dp_ps(mCol[1].mValue, inV.mValue, 0x7f);
+	__m128 xy = _mm_blend_ps(x, y, 0b0010);
+	__m128 z = _mm_dp_ps(mCol[2].mValue, inV.mValue, 0x7f);
+	__m128 xyzz = _mm_blend_ps(xy, z, 0b1100);
+	return xyzz;
+#else
 	return Transposed3x3().Multiply3x3(inV);
+#endif
 }
 
 Mat44 Mat44::Multiply3x3(Mat44Arg inM) const

+ 9 - 9
Jolt/Physics/Body/Body.h

@@ -90,7 +90,7 @@ public:
 	void					SetRestitution(float inRestitution)								{ JPH_ASSERT(inRestitution >= 0.0f && inRestitution <= 1.0f); mRestitution = inRestitution; }
 
 	/// Get world space linear velocity of the center of mass (unit: m/s)
-	inline const Vec3		GetLinearVelocity() const										{ return !IsStatic()? mMotionProperties->GetLinearVelocity() : Vec3::sZero(); }
+	inline Vec3				GetLinearVelocity() const										{ return !IsStatic()? mMotionProperties->GetLinearVelocity() : Vec3::sZero(); }
 
 	/// Set world space linear velocity of the center of mass (unit: m/s)
 	void					SetLinearVelocity(Vec3Arg inLinearVelocity)						{ JPH_ASSERT(!IsStatic()); mMotionProperties->SetLinearVelocity(inLinearVelocity); }
@@ -99,7 +99,7 @@ public:
 	void					SetLinearVelocityClamped(Vec3Arg inLinearVelocity)				{ JPH_ASSERT(!IsStatic()); mMotionProperties->SetLinearVelocityClamped(inLinearVelocity); }
 
 	/// Get world space angular velocity of the center of mass (unit: rad/s)
-	inline const Vec3		GetAngularVelocity() const										{ return !IsStatic()? mMotionProperties->GetAngularVelocity() : Vec3::sZero(); }
+	inline Vec3				GetAngularVelocity() const										{ return !IsStatic()? mMotionProperties->GetAngularVelocity() : Vec3::sZero(); }
 
 	/// Set world space angular velocity of the center of mass (unit: rad/s)
 	void					SetAngularVelocity(Vec3Arg inAngularVelocity)					{ JPH_ASSERT(!IsStatic()); mMotionProperties->SetAngularVelocity(inAngularVelocity); }
@@ -108,10 +108,10 @@ public:
 	void					SetAngularVelocityClamped(Vec3Arg inAngularVelocity)			{ JPH_ASSERT(!IsStatic()); mMotionProperties->SetAngularVelocityClamped(inAngularVelocity); }
 
 	/// Velocity of point inPoint (in center of mass space, e.g. on the surface of the body) of the body (unit: m/s)
-	inline const Vec3		GetPointVelocityCOM(Vec3Arg inPointRelativeToCOM) const			{ return !IsStatic()? mMotionProperties->GetPointVelocityCOM(inPointRelativeToCOM) : Vec3::sZero(); }
+	inline Vec3				GetPointVelocityCOM(Vec3Arg inPointRelativeToCOM) const			{ return !IsStatic()? mMotionProperties->GetPointVelocityCOM(inPointRelativeToCOM) : Vec3::sZero(); }
 
 	/// Velocity of point inPoint (in world space, e.g. on the surface of the body) of the body (unit: m/s)
-	inline const Vec3		GetPointVelocity(Vec3Arg inPoint) const							{ JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); return GetPointVelocityCOM(inPoint - mPosition); }
+	inline Vec3				GetPointVelocity(Vec3Arg inPoint) const							{ JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); return GetPointVelocityCOM(inPoint - mPosition); }
 
 	/// Add force (unit: N) for the next time step, will be reset after the next call to PhysicsSimulation::Update
 	inline void				AddForce(Vec3Arg inForce)										{ JPH_ASSERT(IsDynamic()); (Vec3::sLoadFloat3Unsafe(mMotionProperties->mForce) + inForce).StoreFloat3(&mMotionProperties->mForce); }
@@ -154,22 +154,22 @@ public:
 	inline const Shape *	GetShape() const												{ return mShape; }
 
 	/// World space position of the body
-	inline const Vec3		GetPosition() const												{ JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); return mPosition - mRotation * mShape->GetCenterOfMass(); }
+	inline Vec3				GetPosition() const												{ JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); return mPosition - mRotation * mShape->GetCenterOfMass(); }
 
 	/// World space rotation of the body
-	inline const Quat 		GetRotation() const												{ JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); return mRotation; }
+	inline Quat 			GetRotation() const												{ JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); return mRotation; }
 
 	/// Calculates the transform of this body
-	inline const Mat44		GetWorldTransform() const;
+	inline Mat44			GetWorldTransform() const;
 
 	/// Gets the world space position of this body's center of mass
 	inline Vec3 			GetCenterOfMassPosition() const									{ JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); return mPosition; }
 
 	/// Calculates the transform for this body's center of mass
-	inline const Mat44		GetCenterOfMassTransform() const;
+	inline Mat44			GetCenterOfMassTransform() const;
 
 	/// Calculates the inverse of the transform for this body's center of mass
-	inline const Mat44		GetInverseCenterOfMassTransform() const;
+	inline Mat44			GetInverseCenterOfMassTransform() const;
 
 	/// Get world space bounding box
 	inline const AABox &	GetWorldSpaceBounds() const										{ return mBounds; }

+ 3 - 3
Jolt/Physics/Body/Body.inl

@@ -5,21 +5,21 @@
 
 namespace JPH {
 
-const Mat44 Body::GetWorldTransform() const
+Mat44 Body::GetWorldTransform() const
 {
 	JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); 
 
 	return Mat44::sRotationTranslation(mRotation, GetPosition());
 }
 
-const Mat44 Body::GetCenterOfMassTransform() const
+Mat44 Body::GetCenterOfMassTransform() const
 {
 	JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); 
 
 	return Mat44::sRotationTranslation(mRotation, mPosition);
 }
 
-const Mat44 Body::GetInverseCenterOfMassTransform() const
+Mat44 Body::GetInverseCenterOfMassTransform() const
 {
 	JPH_ASSERT(BodyAccess::sCheckRights(BodyAccess::sPositionAccess, BodyAccess::EAccess::Read)); 
 

+ 2 - 8
Jolt/Physics/Collision/BroadPhase/QuadTree.cpp

@@ -1181,14 +1181,8 @@ void QuadTree::CollideSphere(Vec3Arg inCenter, float inRadius, CollideShapeBodyC
 		/// Visit nodes, returns number of hits found and sorts ioChildNodeIDs so that they are at the beginning of the vector.
 		JPH_INLINE int				VisitNodes(Vec4Arg inBoundsMinX, Vec4Arg inBoundsMinY, Vec4Arg inBoundsMinZ, Vec4Arg inBoundsMaxX, Vec4Arg inBoundsMaxY, Vec4Arg inBoundsMaxZ, UVec4 &ioChildNodeIDs, int inStackTop) const
 		{
-			// Get closest point on box
-			Vec4 closest_x = Vec4::sMin(Vec4::sMax(mCenterX, inBoundsMinX), inBoundsMaxX);
-			Vec4 closest_y = Vec4::sMin(Vec4::sMax(mCenterY, inBoundsMinY), inBoundsMaxY);
-			Vec4 closest_z = Vec4::sMin(Vec4::sMax(mCenterZ, inBoundsMinZ), inBoundsMaxZ);
-
-			// Test the distance from the center of the sphere to the box is smaller than the radius
-			Vec4 distance_sq = Square(closest_x - mCenterX) + Square(closest_y - mCenterY) + Square(closest_z - mCenterZ);
-			UVec4 hitting = Vec4::sLessOrEqual(distance_sq, mRadiusSq);
+			// Test 4 boxes vs sphere
+			UVec4 hitting = AABox4VsSphere(mCenterX, mCenterY, mCenterZ, mRadiusSq, inBoundsMinX, inBoundsMinY, inBoundsMinZ, inBoundsMaxX, inBoundsMaxY, inBoundsMaxZ);
 
 			// Count how many results are hitting
 			int num_results = hitting.CountTrues();

+ 2 - 0
Jolt/Physics/Collision/CastSphereVsTriangles.cpp

@@ -46,6 +46,8 @@ void CastSphereVsTriangles::AddHit(bool inBackFacing, const SubShapeID &inSubSha
 	// Its a hit, store the sub shape id's
 	ShapeCastResult result(inFraction, contact_point_a, contact_point_b, contact_normal_world, inBackFacing, mSubShapeIDCreator1.GetID(), inSubShapeID2, TransformedShape::sGetBodyID(mCollector.GetContext()));
 
+	// Note: We don't gather faces here because that's only useful if both shapes have a face. Since the sphere always has only 1 contact point, the manifold is always a point.
+
 	JPH_IF_TRACK_NARROWPHASE_STATS(TrackNarrowPhaseCollector track;)
 	mCollector.AddHit(result);
 }

+ 0 - 1
Jolt/Physics/Collision/CollideConvexVsTriangles.h

@@ -7,7 +7,6 @@
 #include <Physics/Collision/Shape/Shape.h>
 #include <Physics/Collision/Shape/SubShapeID.h>
 #include <Physics/Collision/Shape/ConvexShape.h>
-#include <atomic>
 
 namespace JPH {
 

+ 112 - 0
Jolt/Physics/Collision/CollideSphereVsTriangles.cpp

@@ -0,0 +1,112 @@
+// SPDX-FileCopyrightText: 2021 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#include <Jolt.h>
+
+#include <Physics/Collision/CollideSphereVsTriangles.h>
+#include <Physics/Collision/Shape/ScaleHelpers.h>
+#include <Physics/Collision/CollideShape.h>
+#include <Physics/Collision/TransformedShape.h>
+#include <Physics/Collision/ActiveEdges.h>
+#include <Physics/Collision/NarrowPhaseStats.h>
+#include <Core/Profiler.h>
+
+namespace JPH {
+
+static constexpr uint8 sClosestFeatureToActiveEdgesMask[] = {
+	0b000,		// 0b000: Invalid, guarded by an assert
+	0b101,		// 0b001: Vertex 1 -> edge 1 or 3
+	0b011,		// 0b010: Vertex 2 -> edge 1 or 2
+	0b001,		// 0b011: Vertex 1 & 2 -> edge 1
+	0b110,		// 0b100: Vertex 3 -> edge 2 or 3
+	0b100,		// 0b101: Vertex 1 & 3 -> edge 3
+	0b010,		// 0b110: Vertex 2 & 3 -> egde 2
+	// 0b111: Vertex 1, 2 & 3 -> interior, guarded by an if
+};
+
+CollideSphereVsTriangles::CollideSphereVsTriangles(const SphereShape *inShape1, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeID &inSubShapeID1, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector) :
+	mCollideShapeSettings(inCollideShapeSettings),
+	mCollector(ioCollector),
+	mShape1(inShape1),
+	mScale2(inScale2),
+	mTransform2(inCenterOfMassTransform2),
+	mSubShapeID1(inSubShapeID1)
+{
+	// Calculate the center of the sphere in the space of 2
+	mSphereCenterIn2 = inCenterOfMassTransform2.Multiply3x3Transposed(inCenterOfMassTransform1.GetTranslation() - inCenterOfMassTransform2.GetTranslation());
+
+	// Determine if shape 2 is inside out or not
+	mScaleSign2 = ScaleHelpers::IsInsideOut(inScale2)? -1.0f : 1.0f;
+
+	// Check that the sphere is uniformly scaled
+	JPH_ASSERT(ScaleHelpers::IsUniformScale(inScale1.Abs()));
+	mRadius = abs(inScale1.GetX()) * inShape1->GetRadius();
+	mRadiusPlusMaxSeparationSq = Square(mRadius + inCollideShapeSettings.mMaxSeparationDistance);
+}
+
+void CollideSphereVsTriangles::Collide(Vec3Arg inV0, Vec3Arg inV1, Vec3Arg inV2, uint8 inActiveEdges, const SubShapeID &inSubShapeID2)
+{
+	JPH_PROFILE_FUNCTION();
+
+	// Scale triangle and make it relative to the center of the sphere
+	Vec3 v0 = mScale2 * inV0 - mSphereCenterIn2; 
+	Vec3 v1 = mScale2 * inV1 - mSphereCenterIn2;
+	Vec3 v2 = mScale2 * inV2 - mSphereCenterIn2;
+
+	// Calculate triangle normal
+	Vec3 triangle_normal = mScaleSign2 * (v1 - v0).Cross(v2 - v0);
+
+	// Backface check
+	bool back_facing = triangle_normal.Dot(v0) > 0.0f;
+	if (mCollideShapeSettings.mBackFaceMode == EBackFaceMode::IgnoreBackFaces && back_facing)
+		return;
+
+	// Check if we collide with the sphere
+	uint32 closest_feature;
+	Vec3 point2 = ClosestPoint::GetClosestPointOnTriangle(v0, v1, v2, closest_feature);
+	float point2_len_sq = point2.LengthSq();
+	if (point2_len_sq > mRadiusPlusMaxSeparationSq)
+		return;
+
+	// Calculate penetration depth
+	float penetration_depth = mRadius - sqrt(point2_len_sq);
+	if (-penetration_depth >= mCollector.GetEarlyOutFraction())
+		return;
+
+	// Calculate penetration axis, direction along which to push 2 to move it out of collision (this is always away from the sphere center)
+	Vec3 penetration_axis = point2.NormalizedOr(Vec3::sAxisY());
+
+	// Calculate the point on the sphere
+	Vec3 point1 = mRadius * penetration_axis;
+
+	// Check if we have enabled active edge detection
+	JPH_ASSERT(closest_feature != 0);
+	if (mCollideShapeSettings.mActiveEdgeMode == EActiveEdgeMode::CollideOnlyWithActive 
+		&& closest_feature != 0b111 // For an interior hit we should already have the right normal
+		&& (inActiveEdges & sClosestFeatureToActiveEdgesMask[closest_feature]) == 0) // If we didn't hit an active edge we should take the triangle normal
+	{
+		// Convert the active edge velocity hint to local space
+		Vec3 active_edge_movement_direction = mTransform2.Multiply3x3Transposed(mCollideShapeSettings.mActiveEdgeMovementDirection);
+
+		// See ActiveEdges::FixNormal. If penetration_axis affects the movement less than the triangle normal we keep penetration_axis.
+		Vec3 new_penetration_axis = back_facing? triangle_normal : -triangle_normal;
+		if (active_edge_movement_direction.Dot(penetration_axis) * new_penetration_axis.Length() >= active_edge_movement_direction.Dot(new_penetration_axis))
+			penetration_axis = new_penetration_axis;
+	}
+
+	// Convert to world space
+	point1 = mTransform2 * (mSphereCenterIn2 + point1);
+	point2 = mTransform2 * (mSphereCenterIn2 + point2);
+	Vec3 penetration_axis_world = mTransform2.Multiply3x3(penetration_axis);
+
+	// Create collision result
+	CollideShapeResult result(point1, point2, penetration_axis_world, penetration_depth, mSubShapeID1, inSubShapeID2, TransformedShape::sGetBodyID(mCollector.GetContext()));
+
+	// Note: We don't gather faces here because that's only useful if both shapes have a face. Since the sphere always has only 1 contact point, the manifold is always a point.
+
+	// Notify the collector
+	JPH_IF_TRACK_NARROWPHASE_STATS(TrackNarrowPhaseCollector track;)
+	mCollector.AddHit(result);
+}
+
+} // JPH

+ 49 - 0
Jolt/Physics/Collision/CollideSphereVsTriangles.h

@@ -0,0 +1,49 @@
+// SPDX-FileCopyrightText: 2021 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#pragma once
+
+#include <Physics/Collision/Shape/Shape.h>
+#include <Physics/Collision/Shape/SubShapeID.h>
+#include <Physics/Collision/Shape/SphereShape.h>
+
+namespace JPH {
+
+class CollideShapeSettings;
+
+/// Collision detection helper that collides a sphere vs one or more triangles
+class CollideSphereVsTriangles
+{
+public:
+	/// Constructor
+	/// @param inShape1 The sphere to collide against triangles
+	/// @param inScale1 Local space scale for the sphere
+	/// @param inScale2 Local space scale for the triangles
+	/// @param inCenterOfMassTransform1 Transform that takes the center of mass of 1 into world space
+	/// @param inCenterOfMassTransform2 Transform that takes the center of mass of 2 into world space
+	/// @param inSubShapeID1 Sub shape ID of the convex object
+	/// @param inCollideShapeSettings Settings for the collide shape query
+	/// @param ioCollector The collector that will receive the results
+									CollideSphereVsTriangles(const SphereShape *inShape1, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeID &inSubShapeID1, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector);
+
+	/// Collide sphere with a single triangle
+	/// @param inV0 , inV1 , inV2: CCW triangle vertices
+	/// @param inActiveEdges bit 0 = edge v0..v1 is active, bit 1 = edge v1..v2 is active, bit 2 = edge v2..v0 is active
+	/// An active edge is an edge that is not connected to another triangle in such a way that it is impossible to collide with the edge
+	/// @param inSubShapeID2 The sub shape ID for the triangle
+	void							Collide(Vec3Arg inV0, Vec3Arg inV1, Vec3Arg inV2, uint8 inActiveEdges, const SubShapeID &inSubShapeID2);
+
+protected:
+	const CollideShapeSettings &	mCollideShapeSettings;					///< Settings for this collision operation
+	CollideShapeCollector &			mCollector;								///< The collector that will receive the results
+	const SphereShape *				mShape1;								///< The shape that we're colliding with
+	Vec3							mScale2;								///< The scale of the shape (in shape local space) of the shape we're colliding against
+	Mat44							mTransform2;							///< Transform of the shape we're colliding against
+	Vec3							mSphereCenterIn2;						///< The center of the sphere in the space of 2
+	SubShapeID						mSubShapeID1;							///< Sub shape ID of colliding shape
+	float							mScaleSign2;							///< Sign of the scale of object 2, -1 if object is inside out, 1 if not
+	float							mRadius;								///< Radius of the sphere
+	float							mRadiusPlusMaxSeparationSq;				///< (Radius + Max SeparationDistance)^2
+};
+
+} // JPH

+ 63 - 0
Jolt/Physics/Collision/Shape/HeightFieldShape.cpp

@@ -15,6 +15,7 @@
 #include <Physics/Collision/CastConvexVsTriangles.h>
 #include <Physics/Collision/CastSphereVsTriangles.h>
 #include <Physics/Collision/CollideConvexVsTriangles.h>
+#include <Physics/Collision/CollideSphereVsTriangles.h>
 #include <Physics/Collision/TransformedShape.h>
 #include <Physics/Collision/ActiveEdges.h>
 #include <Physics/Collision/CollisionDispatch.h>
@@ -1809,6 +1810,67 @@ void HeightFieldShape::sCollideConvexVsHeightField(const Shape *inShape1, const
 	shape2->WalkHeightField(visitor);
 }
 
+void HeightFieldShape::sCollideSphereVsHeightField(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector)
+{
+	JPH_PROFILE_FUNCTION();
+
+	// Get the shapes
+	JPH_ASSERT(inShape1->GetSubType() == EShapeSubType::Sphere);
+	JPH_ASSERT(inShape2->GetType() == EShapeType::HeightField);
+	const SphereShape *shape1 = static_cast<const SphereShape *>(inShape1);
+	const HeightFieldShape *shape2 = static_cast<const HeightFieldShape *>(inShape2);
+
+	struct Visitor : public CollideSphereVsTriangles
+	{
+		using CollideSphereVsTriangles::CollideSphereVsTriangles;
+
+		JPH_INLINE bool				ShouldAbort() const
+		{
+			return mCollector.ShouldEarlyOut();
+		}
+
+		JPH_INLINE bool				ShouldVisitRangeBlock([[maybe_unused]] int inStackTop) const
+		{
+			return true;
+		}
+
+		JPH_INLINE int				VisitRangeBlock(Vec4Arg inBoundsMinX, Vec4Arg inBoundsMinY, Vec4Arg inBoundsMinZ, Vec4Arg inBoundsMaxX, Vec4Arg inBoundsMaxY, Vec4Arg inBoundsMaxZ, UVec4 &ioProperties, [[maybe_unused]] int inStackTop) const
+		{
+			// Scale the bounding boxes of this node
+			Vec4 bounds_min_x, bounds_min_y, bounds_min_z, bounds_max_x, bounds_max_y, bounds_max_z;
+			AABox4Scale(mScale2, inBoundsMinX, inBoundsMinY, inBoundsMinZ, inBoundsMaxX, inBoundsMaxY, inBoundsMaxZ, bounds_min_x, bounds_min_y, bounds_min_z, bounds_max_x, bounds_max_y, bounds_max_z);
+
+			// Test which nodes collide
+			UVec4 collides = AABox4VsSphere(mSphereCenterIn2, mRadiusPlusMaxSeparationSq, bounds_min_x, bounds_min_y, bounds_min_z, bounds_max_x, bounds_max_y, bounds_max_z);
+
+			// Sort so the colliding ones go first
+			UVec4::sSort4True(collides, ioProperties);
+
+			// Return number of hits
+			return collides.CountTrues();
+		}
+
+		JPH_INLINE void				VisitTriangle(uint inX, uint inY, uint inTriangle, Vec3Arg inV0, Vec3Arg inV1, Vec3Arg inV2)
+		{			
+			// Create ID for triangle
+			SubShapeID triangle_sub_shape_id = mShape2->EncodeSubShapeID(mSubShapeIDCreator2, inX, inY, inTriangle);
+
+			// Determine active edges
+			uint8 active_edges = mShape2->GetEdgeFlags(inX, inY, inTriangle);
+
+			Collide(inV0, inV1, inV2, active_edges, triangle_sub_shape_id);
+		}
+
+		const HeightFieldShape *	mShape2;
+		SubShapeIDCreator			mSubShapeIDCreator2;
+	};
+
+	Visitor visitor(shape1, inScale1, inScale2, inCenterOfMassTransform1, inCenterOfMassTransform2, inSubShapeIDCreator1.GetID(), inCollideShapeSettings, ioCollector);
+	visitor.mShape2 = shape2;
+	visitor.mSubShapeIDCreator2 = inSubShapeIDCreator2;
+	shape2->WalkHeightField(visitor);
+}
+
 void HeightFieldShape::SaveBinaryState(StreamOut &inStream) const
 {
 	Shape::SaveBinaryState(inStream);
@@ -1882,6 +1944,7 @@ void HeightFieldShape::sRegister()
 	}
 
 	// Specialized collision functions
+	CollisionDispatch::sRegisterCollideShape(EShapeSubType::Sphere, EShapeSubType::HeightField, sCollideSphereVsHeightField);
 	CollisionDispatch::sRegisterCastShape(EShapeSubType::Sphere, EShapeSubType::HeightField, sCastSphereVsHeightField);
 }
 

+ 1 - 0
Jolt/Physics/Collision/Shape/HeightFieldShape.h

@@ -217,6 +217,7 @@ private:
 
 	// Helper functions called by CollisionDispatch
 	static void						sCollideConvexVsHeightField(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector);
+	static void						sCollideSphereVsHeightField(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector);
 	static void						sCastConvexVsHeightField(const ShapeCast &inShapeCast, const ShapeCastSettings &inShapeCastSettings, const Shape *inShape, Vec3Arg inScale, const ShapeFilter &inShapeFilter, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, CastShapeCollector &ioCollector);
 	static void						sCastSphereVsHeightField(const ShapeCast &inShapeCast, const ShapeCastSettings &inShapeCastSettings, const Shape *inShape, Vec3Arg inScale, const ShapeFilter &inShapeFilter, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, CastShapeCollector &ioCollector);
 

+ 62 - 1
Jolt/Physics/Collision/Shape/MeshShape.cpp

@@ -7,12 +7,14 @@
 #include <Physics/Collision/Shape/MeshShape.h>
 #include <Physics/Collision/Shape/ConvexShape.h>
 #include <Physics/Collision/Shape/ScaleHelpers.h>
+#include <Physics/Collision/Shape/SphereShape.h>
 #include <Physics/Collision/RayCast.h>
 #include <Physics/Collision/ShapeCast.h>
 #include <Physics/Collision/ShapeFilter.h>
 #include <Physics/Collision/CastResult.h>
 #include <Physics/Collision/CollidePointResult.h>
 #include <Physics/Collision/CollideConvexVsTriangles.h>
+#include <Physics/Collision/CollideSphereVsTriangles.h>
 #include <Physics/Collision/CastConvexVsTriangles.h>
 #include <Physics/Collision/CastSphereVsTriangles.h>
 #include <Physics/Collision/TransformedShape.h>
@@ -49,6 +51,7 @@ JPH_IMPLEMENT_SERIALIZABLE_VIRTUAL(MeshShapeSettings)
 	JPH_ADD_ATTRIBUTE(MeshShapeSettings, mTriangleVertices)
 	JPH_ADD_ATTRIBUTE(MeshShapeSettings, mIndexedTriangles)
 	JPH_ADD_ATTRIBUTE(MeshShapeSettings, mMaterials)
+	JPH_ADD_ATTRIBUTE(MeshShapeSettings, mMaxTrianglesPerLeaf)
 }
 
 // Codecs this mesh shape is using
@@ -163,6 +166,13 @@ MeshShape::MeshShape(const MeshShapeSettings &inSettings, ShapeResult &outResult
 			}
 	}
 
+	// Check max triangles
+	if (inSettings.mMaxTrianglesPerLeaf < 1 || inSettings.mMaxTrianglesPerLeaf > MaxTrianglesPerLeaf)
+	{
+		outResult.SetError("Invalid max triangles per leaf");
+		return;
+	}
+
 	// Fill in active edge bits
 	IndexedTriangleList indexed_triangles = inSettings.mIndexedTriangles; // Copy indices since we're adding the 'active edge' flag
 	FindActiveEdges(inSettings.mTriangleVertices, indexed_triangles);
@@ -171,7 +181,7 @@ MeshShape::MeshShape(const MeshShapeSettings &inSettings, ShapeResult &outResult
 	TriangleSplitterBinning splitter(inSettings.mTriangleVertices, indexed_triangles);
 	
 	// Build tree
-	AABBTreeBuilder builder(splitter, MaxTrianglesPerLeaf);
+	AABBTreeBuilder builder(splitter, inSettings.mMaxTrianglesPerLeaf);
 	AABBTreeBuilderStats builder_stats;
 	AABBTreeBuilder::Node *root = builder.Build(builder_stats);
 
@@ -1040,6 +1050,56 @@ void MeshShape::sCollideConvexVsMesh(const Shape *inShape1, const Shape *inShape
 	shape2->WalkTreePerTriangle(inSubShapeIDCreator2, visitor);
 }
 
+void MeshShape::sCollideSphereVsMesh(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector)
+{
+	JPH_PROFILE_FUNCTION();
+
+	// Get the shapes
+	JPH_ASSERT(inShape1->GetSubType() == EShapeSubType::Sphere);
+	JPH_ASSERT(inShape2->GetType() == EShapeType::Mesh);
+	const SphereShape *shape1 = static_cast<const SphereShape *>(inShape1);
+	const MeshShape *shape2 = static_cast<const MeshShape *>(inShape2);
+
+	struct Visitor : public CollideSphereVsTriangles
+	{
+		using CollideSphereVsTriangles::CollideSphereVsTriangles;
+
+		JPH_INLINE bool	ShouldAbort() const
+		{
+			return mCollector.ShouldEarlyOut();
+		}
+
+		JPH_INLINE bool	ShouldVisitNode([[maybe_unused]] int inStackTop) const
+		{
+			return true;
+		}
+
+		JPH_INLINE int	VisitNodes(Vec4Arg inBoundsMinX, Vec4Arg inBoundsMinY, Vec4Arg inBoundsMinZ, Vec4Arg inBoundsMaxX, Vec4Arg inBoundsMaxY, Vec4Arg inBoundsMaxZ, UVec4 &ioProperties, [[maybe_unused]] int inStackTop) const
+		{
+			// Scale the bounding boxes of this node
+			Vec4 bounds_min_x, bounds_min_y, bounds_min_z, bounds_max_x, bounds_max_y, bounds_max_z;
+			AABox4Scale(mScale2, inBoundsMinX, inBoundsMinY, inBoundsMinZ, inBoundsMaxX, inBoundsMaxY, inBoundsMaxZ, bounds_min_x, bounds_min_y, bounds_min_z, bounds_max_x, bounds_max_y, bounds_max_z);
+
+			// Test which nodes collide
+			UVec4 collides = AABox4VsSphere(mSphereCenterIn2, mRadiusPlusMaxSeparationSq, bounds_min_x, bounds_min_y, bounds_min_z, bounds_max_x, bounds_max_y, bounds_max_z);
+
+			// Sort so the colliding ones go first
+			UVec4::sSort4True(collides, ioProperties);
+
+			// Return number of hits
+			return collides.CountTrues();
+		}
+
+		JPH_INLINE void	VisitTriangle(Vec3Arg inV0, Vec3Arg inV1, Vec3Arg inV2, uint8 inActiveEdges, SubShapeID inSubShapeID2) 
+		{
+			Collide(inV0, inV1, inV2, inActiveEdges, inSubShapeID2);
+		}
+	};
+
+	Visitor visitor(shape1, inScale1, inScale2, inCenterOfMassTransform1, inCenterOfMassTransform2, inSubShapeIDCreator1.GetID(), inCollideShapeSettings, ioCollector);
+	shape2->WalkTreePerTriangle(inSubShapeIDCreator2, visitor);
+}
+
 void MeshShape::SaveBinaryState(StreamOut &inStream) const
 {
 	Shape::SaveBinaryState(inStream);
@@ -1114,6 +1174,7 @@ void MeshShape::sRegister()
 	}
 
 	// Specialized collision functions
+	CollisionDispatch::sRegisterCollideShape(EShapeSubType::Sphere, EShapeSubType::Mesh, sCollideSphereVsMesh);
 	CollisionDispatch::sRegisterCastShape(EShapeSubType::Sphere, EShapeSubType::Mesh, sCastSphereVsMesh);
 }
 

+ 5 - 0
Jolt/Physics/Collision/Shape/MeshShape.h

@@ -42,6 +42,10 @@ public:
 
 	/// Materials assigned to the triangles. Each triangle specifies which material it uses through its mMaterialIndex
 	PhysicsMaterialList				mMaterials;
+
+	/// Maximum number of triangles in each leaf of the axis aligned box tree. This is a balance between memory and performance. Can be in the range [1, MeshShape::MaxTrianglesPerLeaf].
+	/// Sensible values are between 4 (for better performance) and 8 (for less memory usage).
+	uint							mMaxTrianglesPerLeaf = 8;
 };
 
 /// A mesh shape, consisting of triangles. Cannot be used as a dynamic object.
@@ -142,6 +146,7 @@ private:
 
 	// Helper functions called by CollisionDispatch
 	static void						sCollideConvexVsMesh(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector);
+	static void						sCollideSphereVsMesh(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector);
 	static void						sCastConvexVsMesh(const ShapeCast &inShapeCast, const ShapeCastSettings &inShapeCastSettings, const Shape *inShape, Vec3Arg inScale, const ShapeFilter &inShapeFilter, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, CastShapeCollector &ioCollector);
 	static void						sCastSphereVsMesh(const ShapeCast &inShapeCast, const ShapeCastSettings &inShapeCastSettings, const Shape *inShape, Vec3Arg inScale, const ShapeFilter &inShapeFilter, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, CastShapeCollector &ioCollector);
 

+ 28 - 0
Jolt/Physics/Collision/Shape/TriangleShape.cpp

@@ -13,6 +13,8 @@
 #include <Physics/Collision/TransformedShape.h>
 #include <Physics/Collision/CastConvexVsTriangles.h>
 #include <Physics/Collision/CastSphereVsTriangles.h>
+#include <Physics/Collision/CollideConvexVsTriangles.h>
+#include <Physics/Collision/CollideSphereVsTriangles.h>
 #include <Physics/Collision/CollisionDispatch.h>
 #include <Geometry/ConvexSupport.h>
 #include <Geometry/RayTriangle.h>
@@ -235,6 +237,28 @@ void TriangleShape::CollidePoint(Vec3Arg inPoint, const SubShapeIDCreator &inSub
 	// Can't be inside a triangle
 }
 
+void TriangleShape::sCollideConvexVsTriangle(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector)
+{
+	JPH_ASSERT(inShape1->GetType() == EShapeType::Convex);
+	const ConvexShape *shape1 = static_cast<const ConvexShape *>(inShape1);
+	JPH_ASSERT(inShape2->GetSubType() == EShapeSubType::Triangle);
+	const TriangleShape *shape2 = static_cast<const TriangleShape *>(inShape2);
+
+	CollideConvexVsTriangles collider(shape1, inScale1, inScale2, inCenterOfMassTransform1, inCenterOfMassTransform2, inSubShapeIDCreator1.GetID(), inCollideShapeSettings, ioCollector);
+	collider.Collide(shape2->mV1, shape2->mV2, shape2->mV3, 0b111, inSubShapeIDCreator2.GetID());
+}
+
+void TriangleShape::sCollideSphereVsTriangle(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector)
+{
+	JPH_ASSERT(inShape1->GetSubType() == EShapeSubType::Sphere);
+	const SphereShape *shape1 = static_cast<const SphereShape *>(inShape1);
+	JPH_ASSERT(inShape2->GetSubType() == EShapeSubType::Triangle);
+	const TriangleShape *shape2 = static_cast<const TriangleShape *>(inShape2);
+
+	CollideSphereVsTriangles collider(shape1, inScale1, inScale2, inCenterOfMassTransform1, inCenterOfMassTransform2, inSubShapeIDCreator1.GetID(), inCollideShapeSettings, ioCollector);
+	collider.Collide(shape2->mV1, shape2->mV2, shape2->mV3, 0b111, inSubShapeIDCreator2.GetID());
+}
+
 void TriangleShape::sCastConvexVsTriangle(const ShapeCast &inShapeCast, const ShapeCastSettings &inShapeCastSettings, const Shape *inShape, Vec3Arg inScale, const ShapeFilter &inShapeFilter, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, CastShapeCollector &ioCollector)
 {
 	JPH_ASSERT(inShape->GetSubType() == EShapeSubType::Triangle);
@@ -340,9 +364,13 @@ void TriangleShape::sRegister()
 	f.mColor = Color::sGreen;
 
 	for (EShapeSubType s : sConvexSubShapeTypes)
+	{
+		CollisionDispatch::sRegisterCollideShape(s, EShapeSubType::Triangle, sCollideConvexVsTriangle);
 		CollisionDispatch::sRegisterCastShape(s, EShapeSubType::Triangle, sCastConvexVsTriangle);
+	}
 
 	// Specialized collision functions
+	CollisionDispatch::sRegisterCollideShape(EShapeSubType::Sphere, EShapeSubType::Triangle, sCollideSphereVsTriangle);
 	CollisionDispatch::sRegisterCastShape(EShapeSubType::Sphere, EShapeSubType::Triangle, sCastSphereVsTriangle);
 }
 

+ 2 - 0
Jolt/Physics/Collision/Shape/TriangleShape.h

@@ -110,6 +110,8 @@ protected:
 
 private:
 	// Helper functions called by CollisionDispatch
+	static void				sCollideConvexVsTriangle(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector);
+	static void				sCollideSphereVsTriangle(const Shape *inShape1, const Shape *inShape2, Vec3Arg inScale1, Vec3Arg inScale2, Mat44Arg inCenterOfMassTransform1, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, const CollideShapeSettings &inCollideShapeSettings, CollideShapeCollector &ioCollector);
 	static void				sCastConvexVsTriangle(const ShapeCast &inShapeCast, const ShapeCastSettings &inShapeCastSettings, const Shape *inShape, Vec3Arg inScale, const ShapeFilter &inShapeFilter, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, CastShapeCollector &ioCollector);
 	static void				sCastSphereVsTriangle(const ShapeCast &inShapeCast, const ShapeCastSettings &inShapeCastSettings, const Shape *inShape, Vec3Arg inScale, const ShapeFilter &inShapeFilter, Mat44Arg inCenterOfMassTransform2, const SubShapeIDCreator &inSubShapeIDCreator1, const SubShapeIDCreator &inSubShapeIDCreator2, CastShapeCollector &ioCollector);
 

+ 5 - 1
PerformanceTest/ConvexVsMeshScene.h

@@ -63,13 +63,17 @@ public:
 				next++;
 			}
 
+		// Create mesh shape settings
+		Ref<MeshShapeSettings> mesh_shape_settings = new MeshShapeSettings(vertices, indices);
+		mesh_shape_settings->mMaxTrianglesPerLeaf = 4;
+
 		// Create mesh shape creation settings
 		mMeshSettings.mMotionType = EMotionType::Static;
 		mMeshSettings.mObjectLayer = Layers::NON_MOVING;
 		mMeshSettings.mPosition = Vec3(-center, max_height, -center);
 		mMeshSettings.mFriction = 0.5f;
 		mMeshSettings.mRestitution = 0.6f;
-		mMeshSettings.SetShapeSettings(new MeshShapeSettings(vertices, indices));
+		mMeshSettings.SetShapeSettings(mesh_shape_settings);
 
 		// Create other shapes
 		mShapes = {

+ 361 - 0
UnitTests/Physics/ConvexVsTrianglesTest.cpp

@@ -0,0 +1,361 @@
+// SPDX-FileCopyrightText: 2021 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#include "UnitTestFramework.h"
+#include "PhysicsTestContext.h"
+#include <Physics/Collision/Shape/SphereShape.h>
+#include <Physics/Collision/Shape/TriangleShape.h>
+#include <Physics/Collision/Shape/MeshShape.h>
+#include <Physics/Collision/CollideShape.h>
+#include <Physics/Collision/CollisionCollectorImpl.h>
+#include <Physics/Collision/CollideConvexVsTriangles.h>
+#include <Physics/Collision/CollideSphereVsTriangles.h>
+#include "Layers.h"
+#include "PhysicsTestContext.h"
+
+TEST_SUITE("ConvexVsTrianglesTest")
+{
+	static constexpr float cEdgeLength = 4.0f;
+
+	template <class Collider>
+	static void sCheckCollisionNoHit(const CollideShapeSettings &inSettings, Vec3Arg inCenter, float inRadius, uint8 inActiveEdges)
+	{
+		// Our sphere
+		Ref<SphereShape> sphere = new SphereShape(inRadius);
+
+		// Our default triangle
+		Vec3 v1(0, 0, 0);
+		Vec3 v2(0, 0, cEdgeLength);
+		Vec3 v3(cEdgeLength, 0, 0);
+				
+		{
+			// Collide sphere
+			AllHitCollisionCollector<CollideShapeCollector> collector;
+			Collider collider(sphere, Vec3::sReplicate(1.0f), Vec3::sReplicate(1.0f), Mat44::sTranslation(inCenter), Mat44::sIdentity(), SubShapeID(), inSettings, collector);
+			collider.Collide(v1, v2, v3, inActiveEdges, SubShapeID());
+			CHECK(!collector.HadHit());
+		}
+
+		// A triangle shape has all edges active, so only test if all edges are active
+		if (inActiveEdges == 0b111)
+		{
+			// Create the triangle shape
+			PhysicsTestContext context;
+			context.CreateBody(new TriangleShapeSettings(v1, v2, v3), Vec3::sZero(), Quat::sIdentity(), EMotionType::Static, EMotionQuality::Discrete, Layers::NON_MOVING, EActivation::DontActivate);
+
+			// Collide sphere
+			AllHitCollisionCollector<CollideShapeCollector> collector;
+			context.GetSystem()->GetNarrowPhaseQuery().CollideShape(sphere, Vec3::sReplicate(1.0f), Mat44::sTranslation(inCenter), inSettings, collector);
+			CHECK(!collector.HadHit());
+		}
+
+		// A mesh shape with a single triangle has all edges active, so only test if all edges are active
+		if (inActiveEdges == 0b111)
+		{
+			// Create a mesh with a single triangle
+			TriangleList triangles;
+			triangles.push_back(Triangle(v1, v2, v3));
+			PhysicsTestContext context;
+			context.CreateBody(new MeshShapeSettings(triangles), Vec3::sZero(), Quat::sIdentity(), EMotionType::Static, EMotionQuality::Discrete, Layers::NON_MOVING, EActivation::DontActivate);
+
+			// Collide sphere
+			AllHitCollisionCollector<CollideShapeCollector> collector;
+			context.GetSystem()->GetNarrowPhaseQuery().CollideShape(sphere, Vec3::sReplicate(1.0f), Mat44::sTranslation(inCenter), inSettings, collector);
+			CHECK(!collector.HadHit());
+		}
+	}
+
+	template <class Collider>
+	static void sCheckCollision(const CollideShapeSettings &inSettings, Vec3Arg inCenter, float inRadius, uint8 inActiveEdges, Vec3Arg inExpectedContactOn1, Vec3Arg inExpectedContactOn2, Vec3Arg inExpectedPenetrationAxis, float inExpectedPenetrationDepth)
+	{
+		// Our sphere
+		Ref<SphereShape> sphere = new SphereShape(inRadius);
+
+		// Our default triangle
+		Vec3 v1(0, 0, 0);
+		Vec3 v2(0, 0, cEdgeLength);
+		Vec3 v3(cEdgeLength, 0, 0);
+
+		// A semi random transform for the triangle
+		Vec3 translation = Vec3(1, 2, 3);
+		Quat rotation = Quat::sRotation(Vec3::sAxisX(), 0.25f * JPH_PI);
+		Mat44 transform = Mat44::sRotationTranslation(rotation, translation);
+		Mat44 inv_transform = transform.InversedRotationTranslation();
+
+		// The transform for the sphere
+		Mat44 sphere_transform = transform * Mat44::sTranslation(inCenter);
+		
+		// Transform incoming settings
+		CollideShapeSettings settings = inSettings;
+		settings.mActiveEdgeMovementDirection = transform.Multiply3x3(inSettings.mActiveEdgeMovementDirection);
+
+		// Test the specified collider
+		{
+			SubShapeID sub_shape_id1, sub_shape_id2;
+			sub_shape_id1.SetValue(123);
+			sub_shape_id2.SetValue(456);
+
+			// Collide sphere
+			AllHitCollisionCollector<CollideShapeCollector> collector;
+			Collider collider(sphere, Vec3::sReplicate(1.0f), Vec3::sReplicate(1.0f), sphere_transform, transform, sub_shape_id1, settings, collector);
+			collider.Collide(v1, v2, v3, inActiveEdges, sub_shape_id2);
+
+			// Test result
+			CHECK(collector.mHits.size() == 1);
+			const CollideShapeResult &hit = collector.mHits[0];
+			CHECK(hit.mBodyID2 == BodyID());
+			CHECK(hit.mSubShapeID1.GetValue() == sub_shape_id1.GetValue());
+			CHECK(hit.mSubShapeID2.GetValue() == sub_shape_id2.GetValue());
+			Vec3 contact1 = inv_transform * hit.mContactPointOn1;
+			Vec3 contact2 = inv_transform * hit.mContactPointOn2;
+			Vec3 pen_axis = transform.Multiply3x3Transposed(hit.mPenetrationAxis).Normalized();
+			Vec3 expected_pen_axis = inExpectedPenetrationAxis.Normalized();
+			CHECK_APPROX_EQUAL(contact1, inExpectedContactOn1, 1.0e-4f);
+			CHECK_APPROX_EQUAL(contact2, inExpectedContactOn2, 1.0e-4f);
+			CHECK_APPROX_EQUAL(pen_axis, expected_pen_axis, 1.0e-4f);
+			CHECK_APPROX_EQUAL(hit.mPenetrationDepth, inExpectedPenetrationDepth, 1.0e-4f);
+		}
+
+		// A triangle shape has all edges active, so only test if all edges are active
+		if (inActiveEdges == 0b111)
+		{
+			// Create the triangle shape
+			PhysicsTestContext context;
+			Body &body = context.CreateBody(new TriangleShapeSettings(v1, v2, v3), translation, rotation, EMotionType::Static, EMotionQuality::Discrete, Layers::NON_MOVING, EActivation::DontActivate);
+
+			// Collide sphere
+			AllHitCollisionCollector<CollideShapeCollector> collector;
+			context.GetSystem()->GetNarrowPhaseQuery().CollideShape(sphere, Vec3::sReplicate(1.0f), sphere_transform, settings, collector);
+
+			// Test result
+			CHECK(collector.mHits.size() == 1);
+			const CollideShapeResult &hit = collector.mHits[0];
+			CHECK(hit.mBodyID2 == body.GetID());
+			CHECK(hit.mSubShapeID1.GetValue() == SubShapeID().GetValue());
+			CHECK(hit.mSubShapeID2.GetValue() == SubShapeID().GetValue());
+			Vec3 contact1 = inv_transform * hit.mContactPointOn1;
+			Vec3 contact2 = inv_transform * hit.mContactPointOn2;
+			Vec3 pen_axis = transform.Multiply3x3Transposed(hit.mPenetrationAxis).Normalized();
+			Vec3 expected_pen_axis = inExpectedPenetrationAxis.Normalized();
+			CHECK_APPROX_EQUAL(contact1, inExpectedContactOn1, 1.0e-4f);
+			CHECK_APPROX_EQUAL(contact2, inExpectedContactOn2, 1.0e-4f);
+			CHECK_APPROX_EQUAL(pen_axis, expected_pen_axis, 1.0e-4f);
+			CHECK_APPROX_EQUAL(hit.mPenetrationDepth, inExpectedPenetrationDepth, 1.0e-4f);
+		}
+
+		// A mesh shape with a single triangle has all edges active, so only test if all edges are active
+		if (inActiveEdges == 0b111)
+		{
+			// Create a mesh with a single triangle
+			TriangleList triangles;
+			triangles.push_back(Triangle(v1, v2, v3));
+			PhysicsTestContext context;
+			Body &body = context.CreateBody(new MeshShapeSettings(triangles), translation, rotation, EMotionType::Static, EMotionQuality::Discrete, Layers::NON_MOVING, EActivation::DontActivate);
+
+			// Collide sphere
+			AllHitCollisionCollector<CollideShapeCollector> collector;
+			context.GetSystem()->GetNarrowPhaseQuery().CollideShape(sphere, Vec3::sReplicate(1.0f), sphere_transform, settings, collector);
+
+			// Test result
+			CHECK(collector.mHits.size() == 1);
+			const CollideShapeResult &hit = collector.mHits[0];
+			CHECK(hit.mBodyID2 == body.GetID());
+			CHECK(hit.mSubShapeID1.GetValue() == SubShapeID().GetValue());
+			CHECK(hit.mSubShapeID2.GetValue() != SubShapeID().GetValue()); // We don't really know what SubShapeID a triangle in the mesh will get, but it should not be invalid
+			Vec3 contact1 = inv_transform * hit.mContactPointOn1;
+			Vec3 contact2 = inv_transform * hit.mContactPointOn2;
+			Vec3 pen_axis = transform.Multiply3x3Transposed(hit.mPenetrationAxis).Normalized();
+			Vec3 expected_pen_axis = inExpectedPenetrationAxis.Normalized();
+			CHECK_APPROX_EQUAL(contact1, inExpectedContactOn1, 1.0e-4f);
+			CHECK_APPROX_EQUAL(contact2, inExpectedContactOn2, 1.0e-4f);
+			CHECK_APPROX_EQUAL(pen_axis, expected_pen_axis, 1.0e-4f);
+			CHECK_APPROX_EQUAL(hit.mPenetrationDepth, inExpectedPenetrationDepth, 1.0e-4f);
+		}
+	}
+
+	// Compares CollideShapeResult for two spheres with given positions and radii
+	template <class Collider>
+	static void sTestConvexVsTriangles()
+	{
+		const float cRadius = 0.5f;
+		const float cRadiusRS2 = cRadius / sqrt(2.0f);
+		const float cDistanceToTriangle = 0.1f;
+		const float cDistanceToTriangleRS2 = cDistanceToTriangle / sqrt(2.0f);
+		const float cEpsilon = 1.0e-6f; // A small epsilon to ensure we hit the front side
+		const float cMaxSeparationDistance = 0.5f;
+		const float cSeparationDistance = 0.1f;
+
+		// Loop over all possible active edge combinations
+		for (uint8 active_edges = 0; active_edges <= 0b111; ++active_edges)
+		{
+			// Create settings
+			CollideShapeSettings settings;
+			settings.mBackFaceMode = EBackFaceMode::CollideWithBackFaces;
+
+			// Settings with ignore back faces
+			CollideShapeSettings settings_no_bf;
+			settings_no_bf.mBackFaceMode = EBackFaceMode::IgnoreBackFaces;
+
+			// Settings with max seperation distance
+			CollideShapeSettings settings_max_distance;
+			settings_max_distance.mBackFaceMode = EBackFaceMode::CollideWithBackFaces;
+			settings_max_distance.mMaxSeparationDistance = cMaxSeparationDistance;
+
+			{
+				// There should be no hit in front of the triangle
+				Vec3 sphere_center(0.25f * cEdgeLength, cRadius + cSeparationDistance, 0.25f * cEdgeLength);
+				sCheckCollisionNoHit<Collider>(settings, sphere_center, cRadius, active_edges);
+
+				// But if there's a max separation distance there should be
+				Vec3 expected1 = sphere_center + Vec3(0, -cRadius, 0);
+				Vec3 expected2(0.25f * cEdgeLength, 0, 0.25f * cEdgeLength);
+				Vec3 pen_axis(0, -1, 0);
+				float pen_depth = -cSeparationDistance;
+				sCheckCollision<Collider>(settings_max_distance, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+			}
+
+			{
+				// But if we go beyond the separation distance we should again have no hit
+				Vec3 sphere_center(0.25f * cEdgeLength, cRadius + cMaxSeparationDistance + cSeparationDistance, 0.25f * cEdgeLength);
+				sCheckCollisionNoHit<Collider>(settings_max_distance, sphere_center, cRadius, active_edges);
+			}
+
+			{
+				// There should be no hit in behind the triangle
+				Vec3 sphere_center(0.25f * cEdgeLength, -cRadius - cSeparationDistance, 0.25f * cEdgeLength);
+				sCheckCollisionNoHit<Collider>(settings, sphere_center, cRadius, active_edges);
+
+				// But if there's a max separation distance there should be
+				Vec3 expected1 = sphere_center + Vec3(0, cRadius, 0);
+				Vec3 expected2(0.25f * cEdgeLength, 0, 0.25f * cEdgeLength);
+				Vec3 pen_axis(0, 1, 0);
+				float pen_depth = -cSeparationDistance;
+				sCheckCollision<Collider>(settings_max_distance, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+			}
+
+			{
+				// But if we go beyond the separation distance we should again have no hit
+				Vec3 sphere_center(0.25f * cEdgeLength, -cRadius - cMaxSeparationDistance - cSeparationDistance, 0.25f * cEdgeLength);
+				sCheckCollisionNoHit<Collider>(settings_max_distance, sphere_center, cRadius, active_edges);
+			}
+
+			{
+				// Hit interior from front side
+				Vec3 expected2(0.25f * cEdgeLength, 0, 0.25f * cEdgeLength);
+				Vec3 sphere_center = expected2 + Vec3(0, cDistanceToTriangle, 0);
+				Vec3 expected1 = sphere_center + Vec3(0, -cRadius, 0);
+				Vec3 pen_axis(0, -1, 0);
+				float pen_depth = cRadius - cDistanceToTriangle;
+				sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+
+				// Ignore back faces should not matter
+				sCheckCollision<Collider>(settings_no_bf, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+			}
+
+			{
+				// Hit interior from back side
+				Vec3 expected2(0.25f * cEdgeLength, 0, 0.25f * cEdgeLength);
+				Vec3 sphere_center = expected2 + Vec3(0, -cDistanceToTriangle, 0);
+				Vec3 expected1 = sphere_center + Vec3(0, cRadius, 0);
+				Vec3 pen_axis(0, 1, 0);
+				float pen_depth = cRadius - cDistanceToTriangle;
+				sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+
+				// Back face hit should be filtered
+				sCheckCollisionNoHit<Collider>(settings_no_bf, sphere_center, cRadius, active_edges);
+			}
+
+			// Loop over possibel active edge movement direction permutations
+			for (int movement_direction = 0; movement_direction < 3; ++movement_direction)
+			{
+				switch (movement_direction)
+				{
+				case 0:
+					// Disable the system
+					settings.mActiveEdgeMovementDirection = Vec3::sZero();
+					break;
+
+				case 1:
+					// Move into the triangle, this should always give us the normal from the edge
+					settings.mActiveEdgeMovementDirection = Vec3(0, -1, 0);
+					break;
+
+				case 2:
+					// Move out of the triangle, we should always get the normal of the triangle
+					settings.mActiveEdgeMovementDirection = Vec3(0, 1, 0);
+					break;
+				}
+		
+				{
+					// Hit edge 1
+					Vec3 expected2(0, 0, 0.5f * cEdgeLength);
+					Vec3 sphere_center = expected2 + Vec3(-cDistanceToTriangle, cEpsilon, 0);
+					Vec3 expected1 = sphere_center + Vec3(cRadius, 0, 0);
+					Vec3 pen_axis = (active_edges & 0b001) != 0 || movement_direction == 1? Vec3(1, 0, 0) : Vec3(0, -1, 0);
+					float pen_depth = cRadius - cDistanceToTriangle;
+					sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+				}
+
+				{
+					// Hit edge 2
+					Vec3 expected2(0.5f * cEdgeLength, 0, 0.5f * cEdgeLength);
+					Vec3 sphere_center = expected2 + Vec3(cDistanceToTriangleRS2, cEpsilon, cDistanceToTriangleRS2);
+					Vec3 expected1 = sphere_center - Vec3(cRadiusRS2, 0, cRadiusRS2);
+					Vec3 pen_axis = (active_edges & 0b010) != 0 || movement_direction == 1? Vec3(-1, 0, -1) : Vec3(0, -1, 0);
+					float pen_depth = cRadius - cDistanceToTriangle;
+					sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+				}
+
+				{
+					// Hit edge 3
+					Vec3 expected2(0.5f * cEdgeLength, 0, 0);
+					Vec3 sphere_center = expected2 + Vec3(0, cEpsilon, -cDistanceToTriangle);
+					Vec3 expected1 = sphere_center + Vec3(0, 0, cRadius);
+					Vec3 pen_axis = (active_edges & 0b100) != 0 || movement_direction == 1? Vec3(0, 0, 1) : Vec3(0, -1, 0);
+					float pen_depth = cRadius - cDistanceToTriangle;
+					sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+				}
+
+				{
+					// Hit vertex 1
+					Vec3 expected2(0, 0, 0);
+					Vec3 sphere_center = expected2 + Vec3(-cDistanceToTriangleRS2, cEpsilon, -cDistanceToTriangleRS2);
+					Vec3 expected1 = sphere_center + Vec3(cRadiusRS2, 0, cRadiusRS2);
+					Vec3 pen_axis = (active_edges & 0b101) != 0 || movement_direction == 1? Vec3(1, 0, 1) : Vec3(0, -1, 0);
+					float pen_depth = cRadius - cDistanceToTriangle;
+					sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+				}
+
+				{
+					// Hit vertex 2
+					Vec3 expected2(0, 0, cEdgeLength);
+					Vec3 sphere_center = expected2 + Vec3(-cDistanceToTriangleRS2, cEpsilon, cDistanceToTriangleRS2);
+					Vec3 expected1 = sphere_center + Vec3(cRadiusRS2, 0, -cRadiusRS2);
+					Vec3 pen_axis = (active_edges & 0b011) != 0 || movement_direction == 1? Vec3(1, 0, -1) : Vec3(0, -1, 0);
+					float pen_depth = cRadius - cDistanceToTriangle;
+					sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+				}
+
+				{
+					// Hit vertex 3
+					Vec3 expected2(cEdgeLength, 0, 0);
+					Vec3 sphere_center = expected2 + Vec3(cDistanceToTriangleRS2, cEpsilon, -cDistanceToTriangleRS2);
+					Vec3 expected1 = sphere_center + Vec3(-cRadiusRS2, 0, cRadiusRS2);
+					Vec3 pen_axis = (active_edges & 0b110) != 0 || movement_direction == 1? Vec3(-1, 0, 1) : Vec3(0, -1, 0);
+					float pen_depth = cRadius - cDistanceToTriangle;
+					sCheckCollision<Collider>(settings, sphere_center, cRadius, active_edges, expected1, expected2, pen_axis, pen_depth);
+				}
+			}
+		}
+	}
+
+	TEST_CASE("TestConvexVsTriangles")
+	{
+		sTestConvexVsTriangles<CollideConvexVsTriangles>();
+	}
+
+	TEST_CASE("TestSphereVsTriangles")
+	{
+		sTestConvexVsTriangles<CollideSphereVsTriangles>();
+	}
+}

+ 1 - 0
UnitTests/UnitTests.cmake

@@ -34,6 +34,7 @@ set(UNIT_TESTS_SRC_FILES
 	${UNIT_TESTS_ROOT}/Physics/CollidePointTests.cpp
 	${UNIT_TESTS_ROOT}/Physics/CollisionGroupTests.cpp
 	${UNIT_TESTS_ROOT}/Physics/ContactListenerTests.cpp
+	${UNIT_TESTS_ROOT}/Physics/ConvexVsTrianglesTest.cpp
 	${UNIT_TESTS_ROOT}/Physics/HeightFieldShapeTests.cpp
 	${UNIT_TESTS_ROOT}/Physics/MotionQualityLinearCastTests.cpp
 	${UNIT_TESTS_ROOT}/Physics/PathConstraintTests.cpp