Ver código fonte

Improvements to soft body constraints (#971)

* Added Long Range Attachment constraint
* Updated Skinned constraint to use back sphere instead of plane
* Added demos for both
Jorrit Rouwe 1 ano atrás
pai
commit
17db6d3f24

+ 11 - 1
Docs/Architecture.md

@@ -251,7 +251,17 @@ After the broad phase has detected an overlap and the normal layer / collision g
 
 The simulation will then proceed to do all collision detection and response and after that is finished, you will receive a SoftBodyContactListener::OnSoftBodyContactAdded callback that allows you to inspect all collisions that happened during the simulation step. In order to do this a SoftBodyManifold is provided which allows you to loop over the vertices and ask each vertex what it collided with.
 
-Note that at the time of the callback, multiple threads are operating at the same time. The soft body is stable and can be safely read. The other body that is collided with is not stable however, so you cannot safely read its position/orientation and velocity as it may be modified by another soft body collision at the same time. 
+Note that at the time of the callback, multiple threads are operating at the same time. The soft body is stable and can be safely read. The other body that is collided with is not stable however, so you cannot safely read its position/orientation and velocity as it may be modified by another soft body collision at the same time.
+
+### Skinning Soft Bodies {#skinning-soft-bodies}
+
+Using the [skinning](@ref SoftBodySharedSettings::Skinned) constraints, a soft body can be (partially) skinned to joints. This can be used e.g. to partially drive cloth with a character animation. The [vertices](@ref SoftBodySharedSettings::Vertex::mPosition) of the soft body need to be placed in the neutral pose of the character and the joints for this pose need to be calculated in model space (relative to these vertices). The inverted matrices of this neutral pose need to be stored as the [inverse bind matrices](@ref SoftBodySharedSettings::InvBind) and the skinning constraints can then be [weighted](@ref SoftBodySharedSettings::SkinWeight) to these joints. SoftBodySharedSettings::CalculateSkinnedConstraintNormals must be called to gather information needed to calculate the face normals at run-time.
+
+At run-time, you need to provide the animated joints every simulation step through the SoftBodyMotionProperties::SkinVertices call. During simulation, each skinned vertex will calculate its position and this position will be used to limit the movement of its simulated counterpart.
+
+![A Skinned Constraint](Images/SoftBodySkinnedConstraint.jpg)
+
+The adjacent faces of the soft body will be used to calculate the normal of each vertex (shown in red), the vertex is then free to move inside the sphere formed by the skinned vertex position with radius [MaxDistance](@ref SoftBodySharedSettings::Skinned::mMaxDistance) (green sphere). To prevent the vertex from intersecting with the character, it is possible to specify a [BackStopDistance](@ref SoftBodySharedSettings::Skinned::mBackStopDistance) and [BackStopRadius](@ref SoftBodySharedSettings::Skinned::mBackStopRadius), together these form the red sphere. The vertex is not allowed to move inside this sphere.
 
 ### Soft Body Work In Progress {#soft-body-wip}
 

BIN
Docs/Images/SoftBodySkinnedConstraint.jpg


+ 16 - 0
Jolt/Core/StreamIn.h

@@ -62,6 +62,22 @@ public:
 			outString.clear();
 	}
 
+	/// Read a vector of primitives from the binary stream using a custom function to read the elements
+	template <class T, class A, typename F>
+	void				Read(std::vector<T, A> &outT, const F &inReadElement)
+	{
+		typename Array<T>::size_type len = outT.size(); // Initialize to previous array size, this is used for validation in the StateRecorder class
+		Read(len);
+		if (!IsEOF() && !IsFailed())
+		{
+			outT.resize(len);
+			for (typename Array<T>::size_type i = 0; i < len; ++i)
+				inReadElement(*this, outT[i]);
+		}
+		else
+			outT.clear();
+	}
+
 	/// Read a Vec3 (don't read W)
 	void				Read(Vec3 &outVec)
 	{

+ 12 - 1
Jolt/Core/StreamOut.h

@@ -28,7 +28,7 @@ public:
 		WriteBytes(&inT, sizeof(inT));
 	}
 
-	/// Write a vector of primitives from the binary stream
+	/// Write a vector of primitives to the binary stream
 	template <class T, class A>
 	void				Write(const std::vector<T, A> &inT)
 	{
@@ -49,6 +49,17 @@ public:
 			WriteBytes(inString.data(), len * sizeof(Type));
 	}
 
+	/// Write a vector of primitives to the binary stream using a custom write function
+	template <class T, class A, typename F>
+	void				Write(const std::vector<T, A> &inT, const F &inWriteElement)
+	{
+		typename Array<T>::size_type len = inT.size();
+		Write(len);
+		if (!IsFailed())
+			for (typename Array<T>::size_type i = 0; i < len; ++i)
+				inWriteElement(inT[i], *this);
+	}
+
 	/// Write a Vec3 (don't write W)
 	void				Write(const Vec3 &inVec)
 	{

+ 7 - 1
Jolt/Physics/Body/BodyManager.cpp

@@ -1079,6 +1079,9 @@ void BodyManager::Draw(const DrawSettings &inDrawSettings, const PhysicsSettings
 				if (inDrawSettings.mDrawSoftBodyVertices)
 					mp->DrawVertices(inRenderer, com);
 
+				if (inDrawSettings.mDrawSoftBodyVertexVelocities)
+					mp->DrawVertexVelocities(inRenderer, com);
+
 				if (inDrawSettings.mDrawSoftBodyEdgeConstraints)
 					mp->DrawEdgeConstraints(inRenderer, com);
 
@@ -1086,7 +1089,10 @@ void BodyManager::Draw(const DrawSettings &inDrawSettings, const PhysicsSettings
 					mp->DrawVolumeConstraints(inRenderer, com);
 
 				if (inDrawSettings.mDrawSoftBodySkinConstraints)
-					mp->DrawSkinConstraints(inRenderer);
+					mp->DrawSkinConstraints(inRenderer, com);
+
+				if (inDrawSettings.mDrawSoftBodyLRAConstraints)
+					mp->DrawLRAConstraints(inRenderer, com);
 
 				if (inDrawSettings.mDrawSoftBodyPredictedBounds)
 					mp->DrawPredictedBounds(inRenderer, com);

+ 2 - 0
Jolt/Physics/Body/BodyManager.h

@@ -230,9 +230,11 @@ public:
 		bool						mDrawMassAndInertia = false;					///< Draw the mass and inertia (as the box equivalent) for each body
 		bool						mDrawSleepStats = false;						///< Draw stats regarding the sleeping algorithm of each body
 		bool						mDrawSoftBodyVertices = false;					///< Draw the vertices of soft bodies
+		bool						mDrawSoftBodyVertexVelocities = false;			///< Draw the velocities of the vertices of soft bodies
 		bool						mDrawSoftBodyEdgeConstraints = false;			///< Draw the edge constraints of soft bodies
 		bool						mDrawSoftBodyVolumeConstraints = false;			///< Draw the volume constraints of soft bodies
 		bool						mDrawSoftBodySkinConstraints = false;			///< Draw the skin constraints of soft bodies
+		bool						mDrawSoftBodyLRAConstraints = false;			///< Draw the LRA constraints of soft bodies
 		bool						mDrawSoftBodyPredictedBounds = false;			///< Draw the predicted bounds of soft bodies
 	};
 

+ 11 - 24
Jolt/Physics/Collision/Shape/CompoundShape.cpp

@@ -305,16 +305,11 @@ void CompoundShape::SaveBinaryState(StreamOut &inStream) const
 	inStream.Write(mInnerRadius);
 
 	// Write sub shapes
-	size_t len = mSubShapes.size();
-	inStream.Write(len);
-	if (!inStream.IsFailed())
-		for (size_t i = 0; i < len; ++i)
-		{
-			const SubShape &s = mSubShapes[i];
-			inStream.Write(s.mUserData);
-			inStream.Write(s.mPositionCOM);
-			inStream.Write(s.mRotation);
-		}
+	inStream.Write(mSubShapes, [](const SubShape &inElement, StreamOut &inS) {
+		inS.Write(inElement.mUserData);
+		inS.Write(inElement.mPositionCOM);
+		inS.Write(inElement.mRotation);
+	});
 }
 
 void CompoundShape::RestoreBinaryState(StreamIn &inStream)
@@ -327,20 +322,12 @@ void CompoundShape::RestoreBinaryState(StreamIn &inStream)
 	inStream.Read(mInnerRadius);
 
 	// Read sub shapes
-	size_t len = 0;
-	inStream.Read(len);
-	if (!inStream.IsEOF() && !inStream.IsFailed())
-	{
-		mSubShapes.resize(len);
-		for (size_t i = 0; i < len; ++i)
-		{
-			SubShape &s = mSubShapes[i];
-			inStream.Read(s.mUserData);
-			inStream.Read(s.mPositionCOM);
-			inStream.Read(s.mRotation);
-			s.mIsRotationIdentity = s.mRotation == Float3(0, 0, 0);
-		}
-	}
+	inStream.Read(mSubShapes, [](StreamIn &inS, SubShape &outElement) {
+		inS.Read(outElement.mUserData);
+		inS.Read(outElement.mPositionCOM);
+		inS.Read(outElement.mRotation);
+		outElement.mIsRotationIdentity = outElement.mRotation == Float3(0, 0, 0);
+	});
 }
 
 void CompoundShape::SaveSubShapeState(ShapeList &outSubShapes) const

+ 62 - 13
Jolt/Physics/SoftBody/SoftBodyMotionProperties.cpp

@@ -307,8 +307,27 @@ void SoftBodyMotionProperties::ApplySkinConstraints([[maybe_unused]] const SoftB
 	{
 		Vertex &vertex = vertices[s.mVertex];
 		const SkinState &skin_state = skin_states[s.mVertex];
-		if (vertex.mInvMass > 0.0f)
+		if (s.mMaxDistance > 0.0f)
 		{
+			// Move vertex if it violated the back stop
+			if (s.mBackStopDistance < s.mMaxDistance)
+			{
+				// Center of the back stop sphere
+				Vec3 center = skin_state.mPosition - skin_state.mNormal * (s.mBackStopDistance + s.mBackStopRadius);
+
+				// Check if we're inside the back stop sphere
+				Vec3 delta = vertex.mPosition - center;
+				float delta_len_sq = delta.LengthSq();
+				if (delta_len_sq < Square(s.mBackStopRadius))
+				{
+					// Push the vertex to the surface of the back stop sphere
+					float delta_len = sqrt(delta_len_sq);
+					vertex.mPosition = delta_len > 0.0f?
+						center + delta * (s.mBackStopRadius / delta_len)
+						: center + skin_state.mNormal * s.mBackStopRadius;
+				}
+			}
+
 			// Clamp vertex distance to max distance from skinned position
 			if (s.mMaxDistance < FLT_MAX)
 			{
@@ -318,15 +337,6 @@ void SoftBodyMotionProperties::ApplySkinConstraints([[maybe_unused]] const SoftB
 				if (delta_len_sq > max_distance_sq)
 					vertex.mPosition = skin_state.mPosition + delta * sqrt(max_distance_sq / delta_len_sq);
 			}
-
-			// Move position if it violated the back stop
-			if (s.mBackStop < s.mMaxDistance)
-			{
-				Vec3 delta = vertex.mPosition - skin_state.mPosition;
-				float violation = -s.mBackStop - skin_state.mNormal.Dot(delta);
-				if (violation > 0.0f)
-					vertex.mPosition += violation * skin_state.mNormal;
-			}
 		}
 		else
 		{
@@ -364,6 +374,26 @@ void SoftBodyMotionProperties::ApplyEdgeConstraints(const SoftBodyUpdateContext
 	}
 }
 
+void SoftBodyMotionProperties::ApplyLRAConstraints()
+{
+	JPH_PROFILE_FUNCTION();
+
+	// Satisfy LRA constraints
+	Vertex *vertices = mVertices.data();
+	for (const LRA &lra : mSettings->mLRAConstraints)
+	{
+		JPH_ASSERT(lra.mVertex[0] < mVertices.size());
+		JPH_ASSERT(lra.mVertex[1] < mVertices.size());
+		const Vertex &vertex0 = vertices[lra.mVertex[0]];
+		Vertex &vertex1 = vertices[lra.mVertex[1]];
+
+		Vec3 delta = vertex1.mPosition - vertex0.mPosition;
+		float delta_len_sq = delta.LengthSq();
+		if (delta_len_sq > Square(lra.mMaxDistance))
+			vertex1.mPosition = vertex0.mPosition + delta * lra.mMaxDistance / sqrt(delta_len_sq);
+	}
+}
+
 void SoftBodyMotionProperties::ApplyCollisionConstraintsAndUpdateVelocities(const SoftBodyUpdateContext &inContext)
 {
 	JPH_PROFILE_FUNCTION();
@@ -670,6 +700,8 @@ SoftBodyMotionProperties::EStatus SoftBodyMotionProperties::ParallelApplyEdgeCon
 						if (non_parallel_group || mSettings->GetEdgeGroupSize(edge_group + 1) == 0)
 						{
 							// Finish the iteration
+							ApplyLRAConstraints();
+
 							ApplyCollisionConstraintsAndUpdateVelocities(ioContext);
 
 							ApplySkinConstraints(ioContext);
@@ -727,7 +759,7 @@ SoftBodyMotionProperties::EStatus SoftBodyMotionProperties::ParallelUpdate(SoftB
 	}
 }
 
-void SoftBodyMotionProperties::SkinVertices(RMat44Arg inRootTransform, const Mat44 *inJointMatrices, [[maybe_unused]] uint inNumJoints, bool inHardSkinAll, TempAllocator &ioTempAllocator)
+void SoftBodyMotionProperties::SkinVertices(RMat44Arg inCenterOfMassTransform, const Mat44 *inJointMatrices, [[maybe_unused]] uint inNumJoints, bool inHardSkinAll, TempAllocator &ioTempAllocator)
 {
 	// Calculate the skin matrices
 	uint num_skin_matrices = uint(mSettings->mInvBindMatrices.size());
@@ -739,7 +771,7 @@ void SoftBodyMotionProperties::SkinVertices(RMat44Arg inRootTransform, const Mat
 		*s = inJointMatrices[inv_bind_matrix->mJointIndex] * inv_bind_matrix->mInvBind;
 
 	// Skin the vertices
-	mSkinStateTransform = inRootTransform;
+	mSkinStateTransform = inCenterOfMassTransform;
 	JPH_IF_ENABLE_ASSERTS(uint num_vertices = uint(mSettings->mVertices.size());)
 	JPH_ASSERT(mSkinState.size() == num_vertices);
 	const SoftBodySharedSettings::Vertex *in_vertices = mSettings->mVertices.data();
@@ -753,6 +785,10 @@ void SoftBodyMotionProperties::SkinVertices(RMat44Arg inRootTransform, const Mat
 		Vec3 pos = Vec3::sZero();
 		for (const SkinWeight &w : s.mWeights)
 		{
+			// We assume that the first zero weight is the end of the list
+			if (w.mWeight == 0.0f)
+				break;
+
 			JPH_ASSERT(w.mInvBindIndex < num_skin_matrices);
 			pos += w.mWeight * (skin_matrices[w.mInvBindIndex] * bind_pos);
 		}
@@ -831,6 +867,12 @@ void SoftBodyMotionProperties::DrawVertices(DebugRenderer *inRenderer, RMat44Arg
 		inRenderer->DrawMarker(inCenterOfMassTransform * v.mPosition, v.mInvMass > 0.0f? Color::sGreen : Color::sRed, 0.05f);
 }
 
+void SoftBodyMotionProperties::DrawVertexVelocities(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const
+{
+	for (const Vertex &v : mVertices)
+		inRenderer->DrawArrow(inCenterOfMassTransform * v.mPosition, inCenterOfMassTransform * (v.mPosition + v.mVelocity), Color::sYellow, 0.01f);
+}
+
 void SoftBodyMotionProperties::DrawEdgeConstraints(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const
 {
 	for (const Edge &e : mSettings->mEdgeConstraints)
@@ -853,15 +895,22 @@ void SoftBodyMotionProperties::DrawVolumeConstraints(DebugRenderer *inRenderer,
 	}
 }
 
-void SoftBodyMotionProperties::DrawSkinConstraints(DebugRenderer *inRenderer) const
+void SoftBodyMotionProperties::DrawSkinConstraints(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const
 {
 	for (const Skinned &s : mSettings->mSkinnedConstraints)
 	{
 		const SkinState &skin_state = mSkinState[s.mVertex];
 		DebugRenderer::sInstance->DrawArrow(mSkinStateTransform * skin_state.mPosition, mSkinStateTransform * (skin_state.mPosition + 0.1f * skin_state.mNormal), Color::sOrange, 0.01f);
+		DebugRenderer::sInstance->DrawLine(mSkinStateTransform * skin_state.mPosition, inCenterOfMassTransform * mVertices[s.mVertex].mPosition, Color::sBlue);
 	}
 }
 
+void SoftBodyMotionProperties::DrawLRAConstraints(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const
+{
+	for (const LRA &l : mSettings->mLRAConstraints)
+		inRenderer->DrawLine(inCenterOfMassTransform * mVertices[l.mVertex[0]].mPosition, inCenterOfMassTransform * mVertices[l.mVertex[1]].mPosition, Color::sGrey);
+}
+
 void SoftBodyMotionProperties::DrawPredictedBounds(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const
 {
 	inRenderer->DrawWireBox(inCenterOfMassTransform, mLocalPredictedBounds, Color::sRed);

+ 10 - 4
Jolt/Physics/SoftBody/SoftBodyMotionProperties.h

@@ -39,6 +39,7 @@ public:
 	using InvBind = SoftBodySharedSettings::InvBind;
 	using SkinWeight = SoftBodySharedSettings::SkinWeight;
 	using Skinned = SoftBodySharedSettings::Skinned;
+	using LRA = SoftBodySharedSettings::LRA;
 
 	/// Initialize the soft body motion properties
 	void								Initialize(const SoftBodyCreationSettings &inSettings);
@@ -87,9 +88,11 @@ public:
 #ifdef JPH_DEBUG_RENDERER
 	/// Draw the state of a soft body
 	void								DrawVertices(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const;
+	void								DrawVertexVelocities(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const;
 	void								DrawEdgeConstraints(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const;
 	void								DrawVolumeConstraints(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const;
-	void								DrawSkinConstraints(DebugRenderer *inRenderer) const;
+	void								DrawSkinConstraints(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const;
+	void								DrawLRAConstraints(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const;
 	void								DrawPredictedBounds(DebugRenderer *inRenderer, RMat44Arg inCenterOfMassTransform) const;
 #endif // JPH_DEBUG_RENDERER
 
@@ -100,12 +103,12 @@ public:
 	void								RestoreState(StateRecorder &inStream);
 
 	/// Skin vertices to supplied joints, information is used by the skinned constraints.
-	/// @param inRootTransform Value of Body::GetCenterOfMassTransform().
-	/// @param inJointMatrices The joint matrices must be expressed relative to inRootTransform.
+	/// @param inCenterOfMassTransform Value of Body::GetCenterOfMassTransform().
+	/// @param inJointMatrices The joint matrices must be expressed relative to inCenterOfMassTransform.
 	/// @param inNumJoints Indicates how large the inJointMatrices array is (used only for validating out of bounds).
 	/// @param inHardSkinAll Can be used to position all vertices on the skinned vertices and can be used to hard reset the soft body.
 	/// @param ioTempAllocator Allocator.
-	void								SkinVertices(RMat44Arg inRootTransform, const Mat44 *inJointMatrices, uint inNumJoints, bool inHardSkinAll, TempAllocator &ioTempAllocator);
+	void								SkinVertices(RMat44Arg inCenterOfMassTransform, const Mat44 *inJointMatrices, uint inNumJoints, bool inHardSkinAll, TempAllocator &ioTempAllocator);
 
 	/// This function allows you to update the soft body immediately without going through the PhysicsSystem.
 	/// This is useful if the soft body is teleported and needs to 'settle' or it can be used if a the soft body
@@ -199,6 +202,9 @@ private:
 	/// Enforce all edge constraints
 	void								ApplyEdgeConstraints(const SoftBodyUpdateContext &inContext, uint inStartIndex, uint inEndIndex);
 
+	/// Enforce all LRA constraints
+	void								ApplyLRAConstraints();
+
 	/// Enforce all collision constraints & update all velocities according the XPBD algorithm
 	void								ApplyCollisionConstraintsAndUpdateVelocities(const SoftBodyUpdateContext &inContext);
 

+ 45 - 15
Jolt/Physics/SoftBody/SoftBodySharedSettings.cpp

@@ -59,7 +59,14 @@ JPH_IMPLEMENT_SERIALIZABLE_NON_VIRTUAL(SoftBodySharedSettings::Skinned)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::Skinned, mVertex)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::Skinned, mWeights)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::Skinned, mMaxDistance)
-	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::Skinned, mBackStop)
+	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::Skinned, mBackStopDistance)
+	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::Skinned, mBackStopRadius)
+}
+
+JPH_IMPLEMENT_SERIALIZABLE_NON_VIRTUAL(SoftBodySharedSettings::LRA)
+{
+	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::LRA, mVertex)
+	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings::LRA, mMaxDistance)
 }
 
 JPH_IMPLEMENT_SERIALIZABLE_NON_VIRTUAL(SoftBodySharedSettings)
@@ -71,6 +78,7 @@ JPH_IMPLEMENT_SERIALIZABLE_NON_VIRTUAL(SoftBodySharedSettings)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings, mVolumeConstraints)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings, mSkinnedConstraints)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings, mInvBindMatrices)
+	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings, mLRAConstraints)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings, mMaterials)
 	JPH_ADD_ATTRIBUTE(SoftBodySharedSettings, mVertexRadius)
 }
@@ -84,6 +92,15 @@ void SoftBodySharedSettings::CalculateEdgeLengths()
 	}
 }
 
+void SoftBodySharedSettings::CalculateLRALengths()
+{
+	for (LRA &l : mLRAConstraints)
+	{
+		l.mMaxDistance = (Vec3(mVertices[l.mVertex[1]].mPosition) - Vec3(mVertices[l.mVertex[0]].mPosition)).Length();
+		JPH_ASSERT(l.mMaxDistance > 0.0f);
+	}
+}
+
 void SoftBodySharedSettings::CalculateVolumeConstraintVolumes()
 {
 	for (Volume &v : mVolumeConstraints)
@@ -208,6 +225,23 @@ void SoftBodySharedSettings::Optimize(OptimizationResults &outResults)
 		mEdgeGroupEndIndices.push_back((uint)mEdgeConstraints.size());
 }
 
+Ref<SoftBodySharedSettings> SoftBodySharedSettings::Clone() const
+{
+	Ref<SoftBodySharedSettings> clone = new SoftBodySharedSettings;
+	clone->mVertices = mVertices;
+	clone->mFaces = mFaces;
+	clone->mEdgeConstraints = mEdgeConstraints;
+	clone->mEdgeGroupEndIndices = mEdgeGroupEndIndices;
+	clone->mVolumeConstraints = mVolumeConstraints;
+	clone->mSkinnedConstraints = mSkinnedConstraints;
+	clone->mSkinnedConstraintNormals = mSkinnedConstraintNormals;
+	clone->mInvBindMatrices = mInvBindMatrices;
+	clone->mLRAConstraints = mLRAConstraints;
+	clone->mMaterials = mMaterials;
+	clone->mVertexRadius = mVertexRadius;
+	return clone;
+}
+
 void SoftBodySharedSettings::SaveBinaryState(StreamOut &inStream) const
 {
 	inStream.Write(mVertices);
@@ -217,15 +251,14 @@ void SoftBodySharedSettings::SaveBinaryState(StreamOut &inStream) const
 	inStream.Write(mVolumeConstraints);
 	inStream.Write(mSkinnedConstraints);
 	inStream.Write(mSkinnedConstraintNormals);
+	inStream.Write(mLRAConstraints);
 	inStream.Write(mVertexRadius);
 
 	// Can't write mInvBindMatrices directly because the class contains padding
-	inStream.Write(uint32(mInvBindMatrices.size()));
-	for (const InvBind &ib : mInvBindMatrices)
-	{
-		inStream.Write(ib.mJointIndex);
-		inStream.Write(ib.mInvBind);
-	}
+	inStream.Write(mInvBindMatrices, [](const InvBind &inElement, StreamOut &inS) {
+		inS.Write(inElement.mJointIndex);
+		inS.Write(inElement.mInvBind);
+	});
 }
 
 void SoftBodySharedSettings::RestoreBinaryState(StreamIn &inStream)
@@ -237,16 +270,13 @@ void SoftBodySharedSettings::RestoreBinaryState(StreamIn &inStream)
 	inStream.Read(mVolumeConstraints);
 	inStream.Read(mSkinnedConstraints);
 	inStream.Read(mSkinnedConstraintNormals);
+	inStream.Read(mLRAConstraints);
 	inStream.Read(mVertexRadius);
 
-	uint32 num_inv_bind_matrices = 0;
-	inStream.Read(num_inv_bind_matrices);
-	mInvBindMatrices.resize(num_inv_bind_matrices);
-	for (InvBind &ib : mInvBindMatrices)
-	{
-		inStream.Read(ib.mJointIndex);
-		inStream.Read(ib.mInvBind);
-	}
+	inStream.Read(mInvBindMatrices, [](StreamIn &inS, InvBind &outElement) {
+		inS.Read(outElement.mJointIndex);
+		inS.Read(outElement.mInvBind);
+	});
 }
 
 void SoftBodySharedSettings::SaveWithMaterials(StreamOut &inStream, SharedSettingsToIDMap &ioSettingsMap, MaterialToIDMap &ioMaterialMap) const

+ 61 - 8
Jolt/Physics/SoftBody/SoftBodySharedSettings.h

@@ -20,6 +20,9 @@ public:
 	/// Calculate the initial lengths of all springs of the edges of this soft body
 	void				CalculateEdgeLengths();
 
+	/// Calculate the max lengths for the long range attachment constraints
+	void				CalculateLRALengths();
+
 	/// Calculates the initial volume of all tetrahedra of this soft body
 	void				CalculateVolumeConstraintVolumes();
 
@@ -39,6 +42,9 @@ public:
 	/// Optimize the soft body settings without results
 	void				Optimize()									{ OptimizationResults results; Optimize(results); }
 
+	/// Clone this object
+	Ref<SoftBodySharedSettings> Clone() const;
+
 	/// Saves the state of this object in binary form to inStream. Doesn't store the material list.
 	void				SaveBinaryState(StreamOut &inStream) const;
 
@@ -122,6 +128,10 @@ public:
 		JPH_DECLARE_SERIALIZABLE_NON_VIRTUAL(JPH_EXPORT, InvBind)
 
 	public:
+		/// Constructor
+						InvBind() = default;
+						InvBind(uint32 inJointIndex, Mat44Arg inInvBind) : mJointIndex(inJointIndex), mInvBind(inInvBind) { }
+
 		uint32			mJointIndex = 0;							///< Joint index to which this is attached
 		Mat44			mInvBind = Mat44::sIdentity();				///< The inverse bind matrix, this takes a vertex in its bind pose (Vertex::mPosition) to joint local space
 	};
@@ -132,6 +142,10 @@ public:
 		JPH_DECLARE_SERIALIZABLE_NON_VIRTUAL(JPH_EXPORT, SkinWeight)
 
 	public:
+		/// Constructor
+						SkinWeight() = default;
+						SkinWeight(uint32 inInvBindIndex, float inWeight) : mInvBindIndex(inInvBindIndex), mWeight(inWeight) { }
+
 		uint32			mInvBindIndex = 0;							///< Index in mInvBindMatrices
 		float			mWeight = 0.0f;								///< Weight with which it is skinned
 	};
@@ -142,29 +156,68 @@ public:
 		JPH_DECLARE_SERIALIZABLE_NON_VIRTUAL(JPH_EXPORT, Skinned)
 
 	public:
+		/// Constructor
+						Skinned() = default;
+						Skinned(uint32 inVertex, float inMaxDistance, float inBackStopDistance, float inBackStopRadius) : mVertex(inVertex), mMaxDistance(inMaxDistance), mBackStopDistance(inBackStopDistance), mBackStopRadius(inBackStopRadius) { }
+
+		/// Normalize the weights so that they add up to 1
+		void			NormalizeWeights()
+		{
+			// Get the total weight
+			float total = 0.0f;
+			for (const SkinWeight &w : mWeights)
+				total += w.mWeight;
+
+			// Normalize
+			if (total > 0.0f)
+				for (SkinWeight &w : mWeights)
+					w.mWeight /= total;
+		}
+
 		uint32			mVertex = 0;								///< Index in mVertices which indicates which vertex is being skinned
-		SkinWeight		mWeights[4];								///< Skin weights, the bind pose of the vertex is assumed to be stored in Vertex::mPosition
-		float			mMaxDistance = FLT_MAX;						///< Maximum distance that this vertex can reach from the skinned vertex, disabled when FLT_MAX
-		float			mBackStop = FLT_MAX;						///< Distance how far behind the skin the vertex can move behind the plane formed by the vertex and the normals of its surrounding faces, if it is bigger than mMaxDistance it is disabled
+		SkinWeight		mWeights[4];								///< Skin weights, the bind pose of the vertex is assumed to be stored in Vertex::mPosition. The first weight that is zero indicates the end of the list. Weights should add up to 1.
+		float			mMaxDistance = FLT_MAX;						///< Maximum distance that this vertex can reach from the skinned vertex, disabled when FLT_MAX. 0 when you want to hard skin the vertex to the skinned vertex.
+		float			mBackStopDistance = FLT_MAX;				///< Disabled if mBackStopDistance >= mMaxDistance. The faces surrounding mVertex determine an average normal. mBackStopDistance behind the vertex in the opposite direction of this normal, the back stop sphere starts. The simulated vertex will be pushed out of this sphere and it can be used to approximate the volume of she skinned mesh behind the skinned vertex.
+		float			mBackStopRadius = 40.0f;					///< Radius of the backstop sphere. By default this is a fairly large radius so the sphere approximates a plane.
 		uint32			mNormalInfo = 0;							///< Information needed to calculate the normal of this vertex, lowest 24 bit is start index in mSkinnedConstraintNormals, highest 8 bit is number of faces (generated by CalculateSkinnedConstraintNormals())
 	};
 
+	/// A long range attachment constraint, this is a constraint that sets a max distance between a kinematic vertex and a dynamic vertex
+	/// See: "Long Range Attachments - A Method to Simulate Inextensible Clothing in Computer Games", Tae-Yong Kim, Nuttapong Chentanez and Matthias Mueller-Fischer
+	class JPH_EXPORT LRA
+	{
+		JPH_DECLARE_SERIALIZABLE_NON_VIRTUAL(JPH_EXPORT, LRA)
+
+	public:
+		/// Constructor
+						LRA() = default;
+						LRA(uint32 inVertex1, uint32 inVertex2, float inMaxDistance) : mVertex { inVertex1, inVertex2 }, mMaxDistance(inMaxDistance) { }
+
+		uint32			mVertex[2];									///< The vertices that are connected. The first vertex should be kinematic, the 2nd dynamic.
+		float			mMaxDistance = 0.0f;						///< The maximum distance between the vertices
+	};
+
 	/// Add a face to this soft body
 	void				AddFace(const Face &inFace)					{ JPH_ASSERT(!inFace.IsDegenerate()); mFaces.push_back(inFace); }
 
-	/// Get the size of an edge group (edge groups can run in parallel)
-	uint				GetEdgeGroupSize(uint inGroupIdx) const		{ return inGroupIdx == 0? mEdgeGroupEndIndices[0] : mEdgeGroupEndIndices[inGroupIdx] - mEdgeGroupEndIndices[inGroupIdx - 1]; }
-
 	Array<Vertex>		mVertices;									///< The list of vertices or particles of the body
 	Array<Face>			mFaces;										///< The list of faces of the body
 	Array<Edge>			mEdgeConstraints;							///< The list of edges or springs of the body
-	Array<uint>			mEdgeGroupEndIndices;						///< The start index of each group of edges that can be solved in parallel
 	Array<Volume>		mVolumeConstraints;							///< The list of volume constraints of the body that keep the volume of tetrahedra in the soft body constant
 	Array<Skinned>		mSkinnedConstraints;						///< The list of vertices that are constrained to a skinned vertex
-	Array<uint32>		mSkinnedConstraintNormals;					///< A list of indices in the mFaces array used by mSkinnedConstraints and calculated by CalculateSkinnedConstraintNormals()
 	Array<InvBind>		mInvBindMatrices;							///< The list of inverse bind matrices for skinning vertices
+	Array<LRA>			mLRAConstraints;							///< The list of long range attachment constraints
 	PhysicsMaterialList mMaterials { PhysicsMaterial::sDefault };	///< The materials of the faces of the body, referenced by Face::mMaterialIndex
 	float				mVertexRadius = 0.0f;						///< How big the particles are, can be used to push the vertices a little bit away from the surface of other bodies to prevent z-fighting
+
+private:
+	friend class SoftBodyMotionProperties;
+
+	/// Get the size of an edge group (edge groups can run in parallel)
+	uint				GetEdgeGroupSize(uint inGroupIdx) const		{ return inGroupIdx == 0? mEdgeGroupEndIndices[0] : mEdgeGroupEndIndices[inGroupIdx] - mEdgeGroupEndIndices[inGroupIdx - 1]; }
+
+	Array<uint>			mEdgeGroupEndIndices;						///< The start index of each group of edges that can be solved in parallel, calculated by Optimize()
+	Array<uint32>		mSkinnedConstraintNormals;					///< A list of indices in the mFaces array used by mSkinnedConstraints, calculated by CalculateSkinnedConstraintNormals()
 };
 
 JPH_NAMESPACE_END

+ 4 - 0
Samples/Samples.cmake

@@ -177,12 +177,16 @@ set(SAMPLES_SRC_FILES
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyGravityFactorTest.h
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyKinematicTest.cpp
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyKinematicTest.h
+	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyLRAConstraintTest.cpp
+	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyLRAConstraintTest.h
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyPressureTest.cpp
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyPressureTest.h
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyRestitutionTest.cpp
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyRestitutionTest.h
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyShapesTest.cpp
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyShapesTest.h
+	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodySkinnedConstraintTest.cpp
+	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodySkinnedConstraintTest.h
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyStressTest.cpp
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyStressTest.h
 	${SAMPLES_ROOT}/Tests/SoftBody/SoftBodyUpdatePositionTest.cpp

+ 8 - 1
Samples/SamplesApp.cpp

@@ -324,6 +324,8 @@ JPH_DECLARE_RTTI_FOR_FACTORY(JPH_NO_EXPORT, SoftBodyVsFastMovingTest)
 JPH_DECLARE_RTTI_FOR_FACTORY(JPH_NO_EXPORT, SoftBodyVertexRadiusTest)
 JPH_DECLARE_RTTI_FOR_FACTORY(JPH_NO_EXPORT, SoftBodyContactListenerTest)
 JPH_DECLARE_RTTI_FOR_FACTORY(JPH_NO_EXPORT, SoftBodyCustomUpdateTest)
+JPH_DECLARE_RTTI_FOR_FACTORY(JPH_NO_EXPORT, SoftBodyLRAConstraintTest)
+JPH_DECLARE_RTTI_FOR_FACTORY(JPH_NO_EXPORT, SoftBodySkinnedConstraintTest)
 
 static TestNameAndRTTI sSoftBodyTests[] =
 {
@@ -338,7 +340,9 @@ static TestNameAndRTTI sSoftBodyTests[] =
 	{ "Soft Body Stress Test",			JPH_RTTI(SoftBodyStressTest) },
 	{ "Soft Body Vertex Radius Test",	JPH_RTTI(SoftBodyVertexRadiusTest) },
 	{ "Soft Body Contact Listener",		JPH_RTTI(SoftBodyContactListenerTest) },
-	{ "Soft Body Custom Update",		JPH_RTTI(SoftBodyCustomUpdateTest) }
+	{ "Soft Body Custom Update",		JPH_RTTI(SoftBodyCustomUpdateTest) },
+	{ "Soft Body LRA Constraint",		JPH_RTTI(SoftBodyLRAConstraintTest) },
+	{ "Soft Body Skinned Constraint",	JPH_RTTI(SoftBodySkinnedConstraintTest) }
 };
 
 JPH_DECLARE_RTTI_FOR_FACTORY(JPH_NO_EXPORT, BroadPhaseCastRayTest)
@@ -518,8 +522,11 @@ SamplesApp::SamplesApp()
 			mDebugUI->CreateCheckBox(drawing_options, "Draw Character Virtual Walk Stairs", CharacterVirtual::sDrawWalkStairs, [](UICheckBox::EState inState) { CharacterVirtual::sDrawWalkStairs = inState == UICheckBox::STATE_CHECKED; });
 			mDebugUI->CreateCheckBox(drawing_options, "Draw Character Virtual Stick To Floor", CharacterVirtual::sDrawStickToFloor, [](UICheckBox::EState inState) { CharacterVirtual::sDrawStickToFloor = inState == UICheckBox::STATE_CHECKED; });
 			mDebugUI->CreateCheckBox(drawing_options, "Draw Soft Body Vertices", mBodyDrawSettings.mDrawSoftBodyVertices, [this](UICheckBox::EState inState) { mBodyDrawSettings.mDrawSoftBodyVertices = inState == UICheckBox::STATE_CHECKED; });
+			mDebugUI->CreateCheckBox(drawing_options, "Draw Soft Body Vertex Velocities", mBodyDrawSettings.mDrawSoftBodyVertexVelocities, [this](UICheckBox::EState inState) { mBodyDrawSettings.mDrawSoftBodyVertexVelocities = inState == UICheckBox::STATE_CHECKED; });
 			mDebugUI->CreateCheckBox(drawing_options, "Draw Soft Body Edge Constraints", mBodyDrawSettings.mDrawSoftBodyEdgeConstraints, [this](UICheckBox::EState inState) { mBodyDrawSettings.mDrawSoftBodyEdgeConstraints = inState == UICheckBox::STATE_CHECKED; });
 			mDebugUI->CreateCheckBox(drawing_options, "Draw Soft Body Volume Constraints", mBodyDrawSettings.mDrawSoftBodyVolumeConstraints, [this](UICheckBox::EState inState) { mBodyDrawSettings.mDrawSoftBodyVolumeConstraints = inState == UICheckBox::STATE_CHECKED; });
+			mDebugUI->CreateCheckBox(drawing_options, "Draw Soft Body Skin Constraints", mBodyDrawSettings.mDrawSoftBodySkinConstraints, [this](UICheckBox::EState inState) { mBodyDrawSettings.mDrawSoftBodySkinConstraints = inState == UICheckBox::STATE_CHECKED; });
+			mDebugUI->CreateCheckBox(drawing_options, "Draw Soft Body LRA Constraints", mBodyDrawSettings.mDrawSoftBodyLRAConstraints, [this](UICheckBox::EState inState) { mBodyDrawSettings.mDrawSoftBodyLRAConstraints = inState == UICheckBox::STATE_CHECKED; });
 			mDebugUI->CreateCheckBox(drawing_options, "Draw Soft Body Predicted Bounds", mBodyDrawSettings.mDrawSoftBodyPredictedBounds, [this](UICheckBox::EState inState) { mBodyDrawSettings.mDrawSoftBodyPredictedBounds = inState == UICheckBox::STATE_CHECKED; });
 			mDebugUI->ShowMenu(drawing_options);
 		});

+ 1 - 1
Samples/Tests/SoftBody/SoftBodyContactListenerTest.cpp

@@ -57,7 +57,7 @@ void SoftBodyContactListenerTest::PrePhysicsUpdate(const PreUpdateParams &inPara
 void SoftBodyContactListenerTest::StartCycle()
 {
 	// Create the cloth
-	Ref<SoftBodySharedSettings> cloth_settings = SoftBodyCreator::CreateCloth(15);
+	Ref<SoftBodySharedSettings> cloth_settings = SoftBodyCreator::CreateClothWithFixatedCorners(15, 15, 0.75f);
 
 	// Create cloth that's fixated at the corners
 	SoftBodyCreationSettings cloth(cloth_settings, RVec3(0, 5, 0), Quat::sRotation(Vec3::sAxisY(), 0.25f * JPH_PI), Layers::MOVING);

+ 38 - 0
Samples/Tests/SoftBody/SoftBodyLRAConstraintTest.cpp

@@ -0,0 +1,38 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2024 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#include <TestFramework.h>
+
+#include <Tests/SoftBody/SoftBodyLRAConstraintTest.h>
+#include <Jolt/Physics/SoftBody/SoftBodyCreationSettings.h>
+#include <Utils/SoftBodyCreator.h>
+#include <Layers.h>
+
+JPH_IMPLEMENT_RTTI_VIRTUAL(SoftBodyLRAConstraintTest)
+{
+	JPH_ADD_BASE_CLASS(SoftBodyLRAConstraintTest, Test)
+}
+
+void SoftBodyLRAConstraintTest::Initialize()
+{
+	CreateFloor();
+
+	// Cloth without LRA constraints
+	auto inv_mass = [](uint, uint inZ) { return inZ == 0? 0.0f : 1.0f; };
+	Ref<SoftBodySharedSettings> cloth_settings = SoftBodyCreator::CreateCloth(cNumVerticesX, cNumVerticesZ, cVertexSpacing, inv_mass);
+	for (SoftBodySharedSettings::Edge &e : cloth_settings->mEdgeConstraints)
+		e.mCompliance = 1.0e-3f; // Soften the edges a bit so that the effect of the LRA constraints is more visible
+	SoftBodyCreationSettings cloth(cloth_settings, RVec3(-10.0f, 25.0f, 0), Quat::sIdentity(), Layers::MOVING);
+	mBodyInterface->CreateAndAddSoftBody(cloth, EActivation::Activate);
+
+	// Cloth with LRA constraints
+	Ref<SoftBodySharedSettings> lra_cloth_settings = cloth_settings->Clone();
+	auto get_vertex = [](uint inX, uint inZ) { return inX + inZ * cNumVerticesX; };
+	for (int z = 1; z < cNumVerticesZ; ++z)
+		for (int x = 0; x < cNumVerticesX; ++x)
+			lra_cloth_settings->mLRAConstraints.push_back(SoftBodySharedSettings::LRA(get_vertex(x, 0), get_vertex(x, z), 0.0f));
+	lra_cloth_settings->CalculateLRALengths();
+	SoftBodyCreationSettings lra_cloth(lra_cloth_settings, RVec3(10.0f, 25.0f, 0), Quat::sIdentity(), Layers::MOVING);
+	mBodyInterface->CreateAndAddSoftBody(lra_cloth, EActivation::Activate);
+}

+ 23 - 0
Samples/Tests/SoftBody/SoftBodyLRAConstraintTest.h

@@ -0,0 +1,23 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2024 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#pragma once
+
+#include <Tests/Test.h>
+
+// This test shows the effect of LRA constraints in a soft body which can help reduce stretch of the cloth. The left cloth uses no LRA constraints and the right one does.
+class SoftBodyLRAConstraintTest : public Test
+{
+public:
+	JPH_DECLARE_RTTI_VIRTUAL(JPH_NO_EXPORT, SoftBodyLRAConstraintTest)
+
+	// See: Test
+	virtual void			Initialize() override;
+
+private:
+	// Size and spacing of the cloth
+	static constexpr int	cNumVerticesX = 10;
+	static constexpr int	cNumVerticesZ = 50;
+	static constexpr float	cVertexSpacing = 0.5f;
+};

+ 1 - 1
Samples/Tests/SoftBody/SoftBodyShapesTest.cpp

@@ -32,7 +32,7 @@ void SoftBodyShapesTest::Initialize()
 	CreateMeshTerrain();
 
 	// Create cloth that's fixated at the corners
-	SoftBodyCreationSettings cloth(SoftBodyCreator::CreateCloth(), RVec3(0, 10.0f, 0), Quat::sRotation(Vec3::sAxisY(), 0.25f * JPH_PI), Layers::MOVING);
+	SoftBodyCreationSettings cloth(SoftBodyCreator::CreateClothWithFixatedCorners(), RVec3(0, 10.0f, 0), Quat::sRotation(Vec3::sAxisY(), 0.25f * JPH_PI), Layers::MOVING);
 	cloth.mUpdatePosition = false; // Don't update the position of the cloth as it is fixed to the world
 	cloth.mMakeRotationIdentity = false; // Test explicitly checks if soft bodies with a rotation collide with shapes properly
 	mBodyInterface->CreateAndAddSoftBody(cloth, EActivation::Activate);

+ 158 - 0
Samples/Tests/SoftBody/SoftBodySkinnedConstraintTest.cpp

@@ -0,0 +1,158 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2024 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#include <TestFramework.h>
+
+#include <Tests/SoftBody/SoftBodySkinnedConstraintTest.h>
+#include <Jolt/Physics/SoftBody/SoftBodyCreationSettings.h>
+#include <Jolt/Physics/SoftBody/SoftBodyMotionProperties.h>
+#include <Utils/SoftBodyCreator.h>
+#include <Layers.h>
+#include <Renderer/DebugRendererImp.h>
+
+JPH_IMPLEMENT_RTTI_VIRTUAL(SoftBodySkinnedConstraintTest)
+{
+	JPH_ADD_BASE_CLASS(SoftBodySkinnedConstraintTest, Test)
+}
+
+Array<Mat44> SoftBodySkinnedConstraintTest::GetWorldSpacePose(float inTime) const
+{
+	Array<Mat44> pose;
+	pose.resize(cNumJoints);
+
+	// Create local space pose
+	pose[0] = Mat44::sTranslation(Vec3(0.0f, cBodyPosY, -0.5f * (cNumVerticesZ - 1) * cVertexSpacing));
+	for (int i = 1; i < cNumJoints; ++i)
+	{
+		float amplitude = 0.25f * min(inTime, 2.0f); // Fade effect in over time
+		Mat44 rotation = Mat44::sRotationX(amplitude * Sin(0.25f * JPH_PI * i + 2.0f * inTime));
+		Mat44 translation = Mat44::sTranslation(Vec3(0, 0, (cNumVerticesZ - 1) * cVertexSpacing / (cNumJoints - 1)));
+		pose[i] = rotation * translation;
+	}
+
+	// Convert to world space
+	for (int i = 1; i < cNumJoints; ++i)
+		pose[i] = pose[i - 1] * pose[i];
+
+	return pose;
+}
+
+void SoftBodySkinnedConstraintTest::SkinVertices(bool inHardSkinAll)
+{
+	RMat44 com = mBody->GetCenterOfMassTransform();
+
+	// Make pose relative to the center of mass of the body
+	Array<Mat44> pose = GetWorldSpacePose(mTime);
+	Mat44 offset = com.InversedRotationTranslation().ToMat44();
+	for (Mat44 &m : pose)
+		m = offset * m;
+
+	SoftBodyMotionProperties *mp = static_cast<SoftBodyMotionProperties *>(mBody->GetMotionProperties());
+	mp->SkinVertices(com, pose.data(), cNumJoints, inHardSkinAll, *mTempAllocator);
+}
+
+void SoftBodySkinnedConstraintTest::Initialize()
+{
+	CreateFloor();
+
+	// Where we'll place the body
+	RVec3 body_translation(0.0f, cBodyPosY, 0);
+
+	// Make first and last row kinematic
+	auto inv_mass = [](uint, uint inZ) { return inZ == 0 || inZ == cNumVerticesZ - 1? 0.0f : 1.0f; };
+	Ref<SoftBodySharedSettings> settings = SoftBodyCreator::CreateCloth(cNumVerticesX, cNumVerticesZ, cVertexSpacing, inv_mass);
+
+	// Make edges soft
+	for (SoftBodySharedSettings::Edge &e : settings->mEdgeConstraints)
+		e.mCompliance = 1.0e-3f;
+
+	// Create inverse bind matrices by moving the bind pose to the center of mass space for the body
+	Array<Mat44> bind_pose = GetWorldSpacePose(0.0f);
+	Mat44 offset = Mat44::sTranslation(Vec3(-body_translation));
+	for (Mat44 &m : bind_pose)
+		m = offset * m;
+	for (int i = 0; i < cNumJoints; ++i)
+		settings->mInvBindMatrices.push_back(SoftBodySharedSettings::InvBind(i, bind_pose[i].Inversed()));
+
+	// Create skinned vertices
+	auto get_vertex = [](uint inX, uint inZ) { return inX + inZ * cNumVerticesX; };
+	for (int z = 0; z < cNumVerticesZ; ++z)
+		for (int x = 0; x < cNumVerticesX; ++x)
+		{
+			uint vertex_idx = get_vertex(x, z);
+			SoftBodySharedSettings::Skinned skinned(vertex_idx, settings->mVertices[vertex_idx].mInvMass > 0.0f? 2.0f : 0.0f, 0.1f, 40.0f);
+
+			// Find closest joints
+			int closest_joint = -1, prev_closest_joint = -1;
+			float closest_joint_dist = FLT_MAX, prev_closest_joint_dist = FLT_MAX;
+			for (int i = 0; i < cNumJoints; ++i)
+			{
+				float dist = abs(settings->mVertices[vertex_idx].mPosition.z - bind_pose[i].GetTranslation().GetZ());
+				if (dist < closest_joint_dist)
+				{
+					prev_closest_joint = closest_joint;
+					prev_closest_joint_dist = closest_joint_dist;
+					closest_joint = i;
+					closest_joint_dist = dist;
+				}
+				else if (dist < prev_closest_joint_dist)
+				{
+					prev_closest_joint = i;
+					prev_closest_joint_dist = dist;
+				}
+			}
+			if (closest_joint_dist == 0.0f)
+			{
+				// Hard skin to closest joint
+				skinned.mWeights[0] = SoftBodySharedSettings::SkinWeight(closest_joint, 1.0f);
+			}
+			else
+			{
+				// Skin to two closest joints
+				skinned.mWeights[0] = SoftBodySharedSettings::SkinWeight(closest_joint, 1.0f / closest_joint_dist);
+				skinned.mWeights[1] = SoftBodySharedSettings::SkinWeight(prev_closest_joint, 1.0f / prev_closest_joint_dist);
+				skinned.NormalizeWeights();
+			}
+
+			settings->mSkinnedConstraints.push_back(skinned);
+		}
+
+	// Calculate the information needed for skinned constraints
+	settings->CalculateSkinnedConstraintNormals();
+
+	// Create the body
+	SoftBodyCreationSettings cloth(settings, body_translation, Quat::sIdentity(), Layers::MOVING);
+	mBody = mBodyInterface->CreateSoftBody(cloth);
+	mBodyInterface->AddBody(mBody->GetID(), EActivation::Activate);
+
+	// Initially hard skin all vertices to the pose
+	SkinVertices(true);
+}
+
+void SoftBodySkinnedConstraintTest::PrePhysicsUpdate(const PreUpdateParams &inParams)
+{
+	// Draw the pose pre step
+	Array<Mat44> pose = GetWorldSpacePose(mTime);
+	for (int i = 1; i < cNumJoints; ++i)
+	{
+		mDebugRenderer->DrawArrow(RVec3(pose[i - 1].GetTranslation()), RVec3(pose[i].GetTranslation()), Color::sGreen, 0.1f);
+		mDebugRenderer->DrawCoordinateSystem(RMat44(pose[i]), 0.5f);
+	}
+
+	// Update time
+	mTime += inParams.mDeltaTime;
+
+	// Calculate skinned vertices but do not hard skin them
+	SkinVertices(false);
+}
+
+void SoftBodySkinnedConstraintTest::SaveState(StateRecorder &inStream) const
+{
+	inStream.Write(mTime);
+}
+
+void SoftBodySkinnedConstraintTest::RestoreState(StateRecorder &inStream)
+{
+	inStream.Read(mTime);
+}

+ 46 - 0
Samples/Tests/SoftBody/SoftBodySkinnedConstraintTest.h

@@ -0,0 +1,46 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2024 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#pragma once
+
+#include <Tests/Test.h>
+#include <Jolt/Physics/Body/Body.h>
+
+// This test shows how to skin a soft body to a skeleton and control the animation.
+class SoftBodySkinnedConstraintTest : public Test
+{
+public:
+	JPH_DECLARE_RTTI_VIRTUAL(JPH_NO_EXPORT, SoftBodySkinnedConstraintTest)
+
+	// See: Test
+	virtual void			Initialize() override;
+	virtual void			PrePhysicsUpdate(const PreUpdateParams &inParams) override;
+	virtual void			GetInitialCamera(CameraState &ioState) const override		{ ioState.mPos = RVec3(15, 30, 15); }
+	virtual void			SaveState(StateRecorder &inStream) const override;
+	virtual void			RestoreState(StateRecorder &inStream) override;
+
+private:
+	// Size and spacing of the cloth
+	static constexpr int	cNumVerticesX = 10;
+	static constexpr int	cNumVerticesZ = 50;
+	static constexpr float	cVertexSpacing = 0.5f;
+
+	// Number of joints that drive the cloth
+	static constexpr int	cNumJoints = 11;
+
+	// Position of the body
+	static constexpr float	cBodyPosY = 20.0f;
+
+	// Get a procedurally generated pose
+	Array<Mat44>			GetWorldSpacePose(float inTime) const;
+
+	// Skin the vertices of the soft body to the pose
+	void					SkinVertices(bool inHardSkinAll);
+
+	// The soft body
+	Body *					mBody;
+
+	// Current time
+	float					mTime = 0.0f;
+};

+ 1 - 1
Samples/Tests/SoftBody/SoftBodyStressTest.cpp

@@ -57,7 +57,7 @@ void SoftBodyStressTest::Initialize()
 		CreateFloor();
 
 		// Create cloth that's fixated at the corners
-		SoftBodyCreationSettings cloth(SoftBodyCreator::CreateCloth(100, 0.25f), RVec3(0, 15.0f, 0), Quat::sIdentity(), Layers::MOVING);
+		SoftBodyCreationSettings cloth(SoftBodyCreator::CreateClothWithFixatedCorners(100, 100, 0.25f), RVec3(0, 15.0f, 0), Quat::sIdentity(), Layers::MOVING);
 		cloth.mUpdatePosition = false; // Don't update the position of the cloth as it is fixed to the world
 		mBodyInterface->CreateAndAddSoftBody(cloth, EActivation::Activate);
 

+ 1 - 1
Samples/Tests/SoftBody/SoftBodyVertexRadiusTest.cpp

@@ -26,7 +26,7 @@ void SoftBodyVertexRadiusTest::Initialize()
 	mBodyInterface->CreateAndAddBody(BodyCreationSettings(new SphereShape(2.0f), RVec3(0, 0, 0), Quat::sIdentity(), EMotionType::Static, Layers::NON_MOVING), EActivation::DontActivate);
 
 	// Create cloth with specified vertex radius
-	mSharedSettings = SoftBodyCreator::CreateCloth(30, 0.5f, false);
+	mSharedSettings = SoftBodyCreator::CreateCloth(30, 30, 0.5f);
 	mSharedSettings->mVertexRadius = sVertexRadius;
 	SoftBodyCreationSettings cloth(mSharedSettings, RVec3(0, 5, 0), Quat::sRotation(Vec3::sAxisY(), 0.25f * JPH_PI), Layers::MOVING);
 	mBodyInterface->CreateAndAddSoftBody(cloth, EActivation::Activate);

+ 1 - 1
Samples/Tests/SoftBody/SoftBodyVsFastMovingTest.cpp

@@ -30,7 +30,7 @@ void SoftBodyVsFastMovingTest::Initialize()
 	mBodyInterface->CreateAndAddBody(bcs, EActivation::Activate);
 
 	// Create cloth that's fixated at the corners
-	SoftBodyCreationSettings cloth(SoftBodyCreator::CreateCloth(), RVec3(0, 15, 0), Quat::sRotation(Vec3::sAxisX(), 0.1f * JPH_PI) * Quat::sRotation(Vec3::sAxisY(), 0.25f * JPH_PI), Layers::MOVING);
+	SoftBodyCreationSettings cloth(SoftBodyCreator::CreateClothWithFixatedCorners(), RVec3(0, 15, 0), Quat::sRotation(Vec3::sAxisX(), 0.1f * JPH_PI) * Quat::sRotation(Vec3::sAxisY(), 0.25f * JPH_PI), Layers::MOVING);
 	cloth.mUpdatePosition = false; // Don't update the position of the cloth as it is fixed to the world
 	cloth.mMakeRotationIdentity = false; // Test explicitly checks if soft bodies with a rotation collide with shapes properly
 	mBodyInterface->CreateAndAddSoftBody(cloth, EActivation::Activate);

+ 48 - 37
Samples/Utils/SoftBodyCreator.cpp

@@ -8,76 +8,75 @@
 
 namespace SoftBodyCreator {
 
-Ref<SoftBodySharedSettings> CreateCloth(uint inGridSize, float inGridSpacing, bool inFixateCorners)
+Ref<SoftBodySharedSettings> CreateCloth(uint inGridSizeX, uint inGridSizeZ, float inGridSpacing, const function<float(uint, uint)> &inVertexGetInvMass)
 {
-	const float cOffset = -0.5f * inGridSpacing * (inGridSize - 1);
+	const float cOffsetX = -0.5f * inGridSpacing * (inGridSizeX - 1);
+	const float cOffsetZ = -0.5f * inGridSpacing * (inGridSizeZ - 1);
 
 	// Create settings
 	SoftBodySharedSettings *settings = new SoftBodySharedSettings;
-	for (uint y = 0; y < inGridSize; ++y)
-		for (uint x = 0; x < inGridSize; ++x)
+	for (uint z = 0; z < inGridSizeZ; ++z)
+		for (uint x = 0; x < inGridSizeX; ++x)
 		{
 			SoftBodySharedSettings::Vertex v;
-			v.mPosition = Float3(cOffset + x * inGridSpacing, 0.0f, cOffset + y * inGridSpacing);
+			v.mPosition = Float3(cOffsetX + x * inGridSpacing, 0.0f, cOffsetZ + z * inGridSpacing);
+			v.mInvMass = inVertexGetInvMass(x, z);
 			settings->mVertices.push_back(v);
 		}
 
 	// Function to get the vertex index of a point on the cloth
-	auto vertex_index = [inGridSize](uint inX, uint inY) -> uint
+	auto vertex_index = [inGridSizeX](uint inX, uint inY) -> uint
 	{
-		return inX + inY * inGridSize;
+		return inX + inY * inGridSizeX;
 	};
 
-	if (inFixateCorners)
-	{
-		// Fixate corners
-		settings->mVertices[vertex_index(0, 0)].mInvMass = 0.0f;
-		settings->mVertices[vertex_index(inGridSize - 1, 0)].mInvMass = 0.0f;
-		settings->mVertices[vertex_index(0, inGridSize - 1)].mInvMass = 0.0f;
-		settings->mVertices[vertex_index(inGridSize - 1, inGridSize - 1)].mInvMass = 0.0f;
-	}
+	// Only add edges if one of the vertices is moveable
+	auto add_edge = [settings](const SoftBodySharedSettings::Edge &inEdge) {
+		if (settings->mVertices[inEdge.mVertex[0]].mInvMass > 0.0f || settings->mVertices[inEdge.mVertex[1]].mInvMass > 0.0f)
+			settings->mEdgeConstraints.push_back(inEdge);
+	};
 
 	// Create edges
-	for (uint y = 0; y < inGridSize; ++y)
-		for (uint x = 0; x < inGridSize; ++x)
+	for (uint z = 0; z < inGridSizeZ; ++z)
+		for (uint x = 0; x < inGridSizeX; ++x)
 		{
 			SoftBodySharedSettings::Edge e;
 			e.mCompliance = 0.00001f;
-			e.mVertex[0] = vertex_index(x, y);
-			if (x < inGridSize - 1)
+			e.mVertex[0] = vertex_index(x, z);
+			if (x < inGridSizeX - 1)
 			{
-				e.mVertex[1] = vertex_index(x + 1, y);
-				settings->mEdgeConstraints.push_back(e);
+				e.mVertex[1] = vertex_index(x + 1, z);
+				add_edge(e);
 			}
-			if (y < inGridSize - 1)
+			if (z < inGridSizeZ - 1)
 			{
-				e.mVertex[1] = vertex_index(x, y + 1);
-				settings->mEdgeConstraints.push_back(e);
+				e.mVertex[1] = vertex_index(x, z + 1);
+				add_edge(e);
 			}
-			if (x < inGridSize - 1 && y < inGridSize - 1)
+			if (x < inGridSizeX - 1 && z < inGridSizeZ - 1)
 			{
-				e.mVertex[1] = vertex_index(x + 1, y + 1);
-				settings->mEdgeConstraints.push_back(e);
+				e.mVertex[1] = vertex_index(x + 1, z + 1);
+				add_edge(e);
 
-				e.mVertex[0] = vertex_index(x + 1, y);
-				e.mVertex[1] = vertex_index(x, y + 1);
-				settings->mEdgeConstraints.push_back(e);
+				e.mVertex[0] = vertex_index(x + 1, z);
+				e.mVertex[1] = vertex_index(x, z + 1);
+				add_edge(e);
 			}
 		}
 	settings->CalculateEdgeLengths();
 
 	// Create faces
-	for (uint y = 0; y < inGridSize - 1; ++y)
-		for (uint x = 0; x < inGridSize - 1; ++x)
+	for (uint z = 0; z < inGridSizeZ - 1; ++z)
+		for (uint x = 0; x < inGridSizeX - 1; ++x)
 		{
 			SoftBodySharedSettings::Face f;
-			f.mVertex[0] = vertex_index(x, y);
-			f.mVertex[1] = vertex_index(x, y + 1);
-			f.mVertex[2] = vertex_index(x + 1, y + 1);
+			f.mVertex[0] = vertex_index(x, z);
+			f.mVertex[1] = vertex_index(x, z + 1);
+			f.mVertex[2] = vertex_index(x + 1, z + 1);
 			settings->AddFace(f);
 
-			f.mVertex[1] = vertex_index(x + 1, y + 1);
-			f.mVertex[2] = vertex_index(x + 1, y);
+			f.mVertex[1] = vertex_index(x + 1, z + 1);
+			f.mVertex[2] = vertex_index(x + 1, z);
 			settings->AddFace(f);
 		}
 
@@ -87,6 +86,18 @@ Ref<SoftBodySharedSettings> CreateCloth(uint inGridSize, float inGridSpacing, bo
 	return settings;
 }
 
+Ref<SoftBodySharedSettings> CreateClothWithFixatedCorners(uint inGridSizeX, uint inGridSizeZ, float inGridSpacing)
+{
+	auto inv_mass = [inGridSizeX, inGridSizeZ](uint inX, uint inZ) {
+		return (inX == 0 && inZ == 0)
+			|| (inX == inGridSizeX - 1 && inZ == 0)
+			|| (inX == 0 && inZ == inGridSizeZ - 1)
+			|| (inX == inGridSizeX - 1 && inZ == inGridSizeZ - 1)? 0.0f : 1.0f;
+	};
+
+	return CreateCloth(inGridSizeX, inGridSizeZ, inGridSpacing, inv_mass);
+}
+
 Ref<SoftBodySharedSettings> CreateCube(uint inGridSize, float inGridSpacing)
 {
 	const Vec3 cOffset = Vec3::sReplicate(-0.5f * inGridSpacing * (inGridSize - 1));

+ 7 - 3
Samples/Utils/SoftBodyCreator.h

@@ -9,10 +9,14 @@
 namespace SoftBodyCreator
 {
 	/// Create a square cloth
-	/// @param inGridSize Number of points along each axis
+	/// @param inGridSizeX Number of points along the X axis
+	/// @param inGridSizeZ Number of points along the Z axis
 	/// @param inGridSpacing Distance between points
-	/// @param inFixateCorners If the corners should be fixated and have infinite mass
-	Ref<SoftBodySharedSettings>	CreateCloth(uint inGridSize = 30, float inGridSpacing = 0.75f, bool inFixateCorners = true);
+	/// @param inVertexGetInvMass Function that determines the inverse mass of each vertex
+	Ref<SoftBodySharedSettings>	CreateCloth(uint inGridSizeX = 30, uint inGridSizeZ = 30, float inGridSpacing = 0.75f, const function<float(uint, uint)> &inVertexGetInvMass = [](uint, uint) { return 1.0f; });
+
+	/// Same as above but fixates the corners of the cloth
+	Ref<SoftBodySharedSettings>	CreateClothWithFixatedCorners(uint inGridSizeX = 30, uint inGridSizeZ = 30, float inGridSpacing = 0.75f);
 
 	/// Create a cube
 	/// @param inGridSize Number of points along each axis