Explorar o código

Created vehicle wheel collision test based on cylinders (#472)

Also fixes outSuspensionLength parameter to really be the suspension length instead of the suspension length + wheel radius
Jorrit Rouwe %!s(int64=2) %!d(string=hai) anos
pai
achega
fcd9cb0f16

+ 96 - 7
Jolt/Physics/Vehicle/VehicleCollisionTester.cpp

@@ -5,22 +5,27 @@
 #include <Jolt/Jolt.h>
 
 #include <Jolt/Physics/Vehicle/VehicleCollisionTester.h>
+#include <Jolt/Physics/Vehicle/VehicleConstraint.h>
 #include <Jolt/Physics/Collision/RayCast.h>
 #include <Jolt/Physics/Collision/ShapeCast.h>
 #include <Jolt/Physics/Collision/CastResult.h>
 #include <Jolt/Physics/Collision/Shape/SphereShape.h>
+#include <Jolt/Physics/Collision/Shape/CylinderShape.h>
 #include <Jolt/Physics/Collision/CollisionCollectorImpl.h>
 #include <Jolt/Physics/PhysicsSystem.h>
 
 JPH_NAMESPACE_BEGIN
 
-bool VehicleCollisionTesterRay::Collide(PhysicsSystem &inPhysicsSystem, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, float inSuspensionMaxLength, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const
+bool VehicleCollisionTesterRay::Collide(PhysicsSystem &inPhysicsSystem, const VehicleConstraint &inVehicleConstraint, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const
 {
 	DefaultBroadPhaseLayerFilter broadphase_layer_filter = inPhysicsSystem.GetDefaultBroadPhaseLayerFilter(mObjectLayer);
 	DefaultObjectLayerFilter object_layer_filter = inPhysicsSystem.GetDefaultLayerFilter(mObjectLayer);
 	IgnoreSingleBodyFilter body_filter(inVehicleBodyID);
 
-	RRayCast ray { inOrigin, inSuspensionMaxLength * inDirection };
+	const WheelSettings *wheel_settings = inVehicleConstraint.GetWheel(inWheelIndex)->GetSettings();
+	float wheel_radius = wheel_settings->mRadius;
+	float ray_length = wheel_settings->mSuspensionMaxLength + wheel_radius;
+	RRayCast ray { inOrigin, ray_length * inDirection };
 
 	class MyCollector : public CastRayCollector
 	{
@@ -87,12 +92,12 @@ bool VehicleCollisionTesterRay::Collide(PhysicsSystem &inPhysicsSystem, uint inW
 	outSubShapeID = collector.mSubShapeID2;
 	outContactPosition = collector.mContactPosition;
 	outContactNormal = collector.mContactNormal;
-	outSuspensionLength = inSuspensionMaxLength * collector.GetEarlyOutFraction();
+	outSuspensionLength = max(0.0f, ray_length * collector.GetEarlyOutFraction() - wheel_radius);
 
 	return true;
 }
 
-bool VehicleCollisionTesterCastSphere::Collide(PhysicsSystem &inPhysicsSystem, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, float inSuspensionMaxLength, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const
+bool VehicleCollisionTesterCastSphere::Collide(PhysicsSystem &inPhysicsSystem, const VehicleConstraint &inVehicleConstraint, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const
 {
 	DefaultBroadPhaseLayerFilter broadphase_layer_filter = inPhysicsSystem.GetDefaultBroadPhaseLayerFilter(mObjectLayer);
 	DefaultObjectLayerFilter object_layer_filter = inPhysicsSystem.GetDefaultLayerFilter(mObjectLayer);
@@ -101,8 +106,10 @@ bool VehicleCollisionTesterCastSphere::Collide(PhysicsSystem &inPhysicsSystem, u
 	SphereShape sphere(mRadius);
 	sphere.SetEmbedded();
 
-	float cast_length = max(0.0f, inSuspensionMaxLength - mRadius);
-	RShapeCast shape_cast(&sphere, Vec3::sReplicate(1.0f), RMat44::sTranslation(inOrigin), inDirection * cast_length);
+	const WheelSettings *wheel_settings = inVehicleConstraint.GetWheel(inWheelIndex)->GetSettings();
+	float wheel_radius = wheel_settings->mRadius;
+	float shape_cast_length = wheel_settings->mSuspensionMaxLength + wheel_radius - mRadius;
+	RShapeCast shape_cast(&sphere, Vec3::sReplicate(1.0f), RMat44::sTranslation(inOrigin), inDirection * shape_cast_length);
 
 	ShapeCastSettings settings;
 	settings.mUseShrunkenShapeAndConvexRadius = true;
@@ -170,7 +177,89 @@ bool VehicleCollisionTesterCastSphere::Collide(PhysicsSystem &inPhysicsSystem, u
 	outSubShapeID = collector.mSubShapeID2;
 	outContactPosition = collector.mContactPosition;
 	outContactNormal = collector.mContactNormal;
-	outSuspensionLength = min(inSuspensionMaxLength, cast_length * collector.GetEarlyOutFraction() + mRadius);
+	outSuspensionLength = max(0.0f, shape_cast_length * collector.GetEarlyOutFraction() + mRadius - wheel_radius);
+
+	return true;
+}
+
+bool VehicleCollisionTesterCastCylinder::Collide(PhysicsSystem &inPhysicsSystem, const VehicleConstraint &inVehicleConstraint, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const
+{
+	DefaultBroadPhaseLayerFilter broadphase_layer_filter = inPhysicsSystem.GetDefaultBroadPhaseLayerFilter(mObjectLayer);
+	DefaultObjectLayerFilter object_layer_filter = inPhysicsSystem.GetDefaultLayerFilter(mObjectLayer);
+	IgnoreSingleBodyFilter body_filter(inVehicleBodyID);
+
+	const WheelSettings *wheel_settings = inVehicleConstraint.GetWheel(inWheelIndex)->GetSettings();
+	float max_suspension_length = wheel_settings->mSuspensionMaxLength;
+
+	// Get the wheel transform given that the cylinder rotates around the Y axis
+	RMat44 shape_cast_start = inVehicleConstraint.GetWheelWorldTransform(inWheelIndex, Vec3::sAxisY(), Vec3::sAxisX());
+	shape_cast_start.SetTranslation(inOrigin);
+
+	// Construct a cylinder with the dimensions of the wheel
+	float wheel_half_width = 0.5f * wheel_settings->mWidth;
+	CylinderShape cylinder(wheel_half_width, wheel_settings->mRadius, min(wheel_half_width, wheel_settings->mRadius) * mConvexRadiusFraction);
+	cylinder.SetEmbedded();
+
+	RShapeCast shape_cast(&cylinder, Vec3::sReplicate(1.0f), shape_cast_start, inDirection * max_suspension_length);
+
+	ShapeCastSettings settings;
+	settings.mUseShrunkenShapeAndConvexRadius = true;
+	settings.mReturnDeepestPoint = true;
+
+	class MyCollector : public CastShapeCollector
+	{
+	public:
+							MyCollector(PhysicsSystem &inPhysicsSystem, const RShapeCast &inShapeCast) : 
+			mPhysicsSystem(inPhysicsSystem),
+			mShapeCast(inShapeCast)
+		{
+		}
+
+		virtual void		AddHit(const ShapeCastResult &inResult) override
+		{
+			// Test if this collision is closer than the previous one
+			if (inResult.mFraction < GetEarlyOutFraction())
+			{
+				// Lock the body
+				BodyLockRead lock(mPhysicsSystem.GetBodyLockInterfaceNoLock(), inResult.mBodyID2);
+				JPH_ASSERT(lock.Succeeded()); // When this runs all bodies are locked so this should not fail
+				const Body *body = &lock.GetBody();
+
+				if (body->IsSensor())
+					return;
+
+				// Update early out fraction to this hit
+				UpdateEarlyOutFraction(inResult.mFraction);
+
+				// Get the contact properties
+				mBody = body;
+				mSubShapeID2 = inResult.mSubShapeID2;
+				mContactPosition = mShapeCast.mCenterOfMassStart.GetTranslation() + inResult.mContactPointOn2;
+				mContactNormal = -inResult.mPenetrationAxis.Normalized();
+			}
+		}
+
+		// Configuration
+		PhysicsSystem &		mPhysicsSystem;
+		const RShapeCast &	mShapeCast;
+
+		// Resulting closest collision
+		const Body *		mBody = nullptr;
+		SubShapeID			mSubShapeID2;
+		RVec3				mContactPosition;
+		Vec3				mContactNormal;
+	};
+
+	MyCollector collector(inPhysicsSystem, shape_cast);
+	inPhysicsSystem.GetNarrowPhaseQueryNoLock().CastShape(shape_cast, settings, shape_cast.mCenterOfMassStart.GetTranslation(), collector, broadphase_layer_filter, object_layer_filter, body_filter);
+	if (collector.mBody == nullptr)
+		return false;
+
+	outBody = const_cast<Body *>(collector.mBody);
+	outSubShapeID = collector.mSubShapeID2;
+	outContactPosition = collector.mContactPosition;
+	outContactNormal = collector.mContactNormal;
+	outSuspensionLength = max_suspension_length * collector.GetEarlyOutFraction();
 
 	return true;
 }

+ 24 - 4
Jolt/Physics/Vehicle/VehicleCollisionTester.h

@@ -9,6 +9,7 @@
 JPH_NAMESPACE_BEGIN
 
 class PhysicsSystem;
+class VehicleConstraint;
 
 /// Class that does collision detection between wheels and ground
 class VehicleCollisionTester : public RefTarget<VehicleCollisionTester>
@@ -21,10 +22,10 @@ public:
 
 	/// Do a collision test with the world
 	/// @param inPhysicsSystem The physics system that should be tested against
+	/// @param inVehicleConstraint The vehicle constraint
 	/// @param inWheelIndex Index of the wheel that we're testing collision for
 	/// @param inOrigin Origin for the test, corresponds to the world space position for the suspension attachment point
 	/// @param inDirection Direction for the test (unit vector, world space)
-	/// @param inSuspensionMaxLength Length of the suspension at max droop (m)
 	/// @param inVehicleBodyID This body should be filtered out during collision detection to avoid self collisions
 	/// @param outBody Body that the wheel collided with
 	/// @param outSubShapeID Sub shape ID that the wheel collided with
@@ -32,7 +33,7 @@ public:
 	/// @param outContactNormal Contact normal between wheel and floor, pointing away from the floor
 	/// @param outSuspensionLength New length of the suspension [0, inSuspensionMaxLength]
 	/// @return True when collision found, false if not
-	virtual bool				Collide(PhysicsSystem &inPhysicsSystem, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, float inSuspensionMaxLength, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const = 0;
+	virtual bool				Collide(PhysicsSystem &inPhysicsSystem, const VehicleConstraint &inVehicleConstraint, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const = 0;
 };
 
 /// Collision tester that tests collision using a raycast
@@ -48,7 +49,7 @@ public:
 								VehicleCollisionTesterRay(ObjectLayer inObjectLayer, Vec3Arg inUp = Vec3::sAxisY(), float inMaxSlopeAngle = DegreesToRadians(80.0f)) : mObjectLayer(inObjectLayer), mUp(inUp), mCosMaxSlopeAngle(Cos(inMaxSlopeAngle)) { }
 
 	// See: VehicleCollisionTester
-	virtual bool				Collide(PhysicsSystem &inPhysicsSystem, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, float inSuspensionMaxLength, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const override;
+	virtual bool				Collide(PhysicsSystem &inPhysicsSystem, const VehicleConstraint &inVehicleConstraint, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const override;
 
 private:
 	ObjectLayer					mObjectLayer;
@@ -70,7 +71,7 @@ public:
 								VehicleCollisionTesterCastSphere(ObjectLayer inObjectLayer, float inRadius, Vec3Arg inUp = Vec3::sAxisY(), float inMaxSlopeAngle = DegreesToRadians(80.0f)) : mObjectLayer(inObjectLayer), mRadius(inRadius), mUp(inUp), mCosMaxSlopeAngle(Cos(inMaxSlopeAngle)) { }
 
 	// See: VehicleCollisionTester
-	virtual bool				Collide(PhysicsSystem &inPhysicsSystem, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, float inSuspensionMaxLength, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const override;
+	virtual bool				Collide(PhysicsSystem &inPhysicsSystem, const VehicleConstraint &inVehicleConstraint, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const override;
 
 private:
 	ObjectLayer					mObjectLayer;
@@ -79,4 +80,23 @@ private:
 	float						mCosMaxSlopeAngle;
 };
 
+/// Collision tester that tests collision using a cylinder shape
+class VehicleCollisionTesterCastCylinder : public VehicleCollisionTester
+{
+public:
+	JPH_OVERRIDE_NEW_DELETE
+
+	/// Constructor
+	/// @param inObjectLayer Object layer to test collision with
+	/// @param inConvexRadiusFraction Fraction of half the wheel width (or wheel radius if it is smaller) that is used as the convex radius
+								VehicleCollisionTesterCastCylinder(ObjectLayer inObjectLayer, float inConvexRadiusFraction = 0.1f) : mObjectLayer(inObjectLayer), mConvexRadiusFraction(inConvexRadiusFraction) { }
+
+	// See: VehicleCollisionTester
+	virtual bool				Collide(PhysicsSystem &inPhysicsSystem, const VehicleConstraint &inVehicleConstraint, uint inWheelIndex, RVec3Arg inOrigin, Vec3Arg inDirection, const BodyID &inVehicleBodyID, Body *&outBody, SubShapeID &outSubShapeID, RVec3 &outContactPosition, Vec3 &outContactNormal, float &outSuspensionLength) const override;
+
+private:
+	ObjectLayer					mObjectLayer;
+	float						mConvexRadiusFraction;
+};
+
 JPH_NAMESPACE_END

+ 11 - 13
Jolt/Physics/Vehicle/VehicleConstraint.cpp

@@ -130,7 +130,7 @@ Mat44 VehicleConstraint::GetWheelLocalTransform(uint inWheelIndex, Vec3Arg inWhe
 	// Calculate the matrix that takes us from the rotational space to vehicle local space
 	Vec3 local_forward = Quat::sRotation(mUp, wheel->mSteerAngle) * mForward;
 	Vec3 local_right = local_forward.Cross(mUp);
-	Vec3 local_wheel_pos = settings->mPosition + settings->mDirection * (wheel->mContactLength - settings->mRadius);
+	Vec3 local_wheel_pos = settings->mPosition + settings->mDirection * wheel->mSuspensionLength;
 	Mat44 rotational_to_local(Vec4(local_right, 0), Vec4(mUp, 0), Vec4(local_forward, 0), Vec4(local_wheel_pos, 1));
 
 	// Calculate transform of rotated wheel
@@ -162,13 +162,12 @@ void VehicleConstraint::OnStep(float inDeltaTime, PhysicsSystem &inPhysicsSystem
 		w->mContactBodyID = BodyID();
 		w->mContactBody = nullptr;
 		w->mContactSubShapeID = SubShapeID();
-		float max_len = settings->mSuspensionMaxLength + settings->mRadius;
-		w->mContactLength = max_len;
+		w->mSuspensionLength = settings->mSuspensionMaxLength;
 
 		// Test collision to find the floor
 		RVec3 origin = mBody->GetCenterOfMassPosition() + mBody->GetRotation() * (settings->mPosition - mBody->GetShape()->GetCenterOfMass());
 		w->mWSDirection = mBody->GetRotation() * settings->mDirection;
-		if (mVehicleCollisionTester->Collide(inPhysicsSystem, wheel_index, origin, w->mWSDirection, max_len, mBody->GetID(), w->mContactBody, w->mContactSubShapeID, w->mContactPosition, w->mContactNormal, w->mContactLength))
+		if (mVehicleCollisionTester->Collide(inPhysicsSystem, *this, wheel_index, origin, w->mWSDirection, mBody->GetID(), w->mContactBody, w->mContactSubShapeID, w->mContactPosition, w->mContactNormal, w->mSuspensionLength))
 		{
 			// Store ID (pointer is not valid outside of the simulation step)
 			w->mContactBodyID = w->mContactBody->GetID();
@@ -197,7 +196,7 @@ void VehicleConstraint::OnStep(float inDeltaTime, PhysicsSystem &inPhysicsSystem
 		if (lw->mContactBody != nullptr && rw->mContactBody != nullptr)
 		{
 			// Calculate the impulse to apply based on the difference in suspension length
-			float difference = rw->mContactLength - lw->mContactLength;
+			float difference = rw->mSuspensionLength - lw->mSuspensionLength;
 			float impulse = difference * r.mStiffness * inDeltaTime;
 			lw->mAntiRollBarImpulse = -impulse;
 			rw->mAntiRollBarImpulse = impulse;
@@ -285,11 +284,10 @@ uint VehicleConstraint::BuildIslandSplits(LargeIslandSplitter &ioSplitter) const
 	return ioSplitter.AssignToNonParallelSplit(mBody);
 }
 
-void VehicleConstraint::CalculateWheelContactPoint(RMat44Arg inBodyTransform, const Wheel &inWheel, Vec3 &outR1PlusU, Vec3 &outR2) const
+void VehicleConstraint::CalculateWheelContactPoint(const Wheel &inWheel, Vec3 &outR1PlusU, Vec3 &outR2) const
 {
-	RVec3 contact_pos = inBodyTransform * (inWheel.mSettings->mPosition + inWheel.mSettings->mDirection * inWheel.mContactLength);
-	outR1PlusU = Vec3(contact_pos - mBody->GetCenterOfMassPosition());
-	outR2 = Vec3(contact_pos - inWheel.mContactBody->GetCenterOfMassPosition());
+	outR1PlusU = Vec3(inWheel.mContactPosition - mBody->GetCenterOfMassPosition());
+	outR2 = Vec3(inWheel.mContactPosition - inWheel.mContactBody->GetCenterOfMassPosition());
 }
 
 void VehicleConstraint::CalculatePitchRollConstraintProperties(float inDeltaTime, RMat44Arg inBodyTransform)
@@ -327,16 +325,16 @@ void VehicleConstraint::SetupVelocityConstraint(float inDeltaTime)
 			const WheelSettings *settings = w->mSettings;
 
 			Vec3 r1_plus_u, r2;
-			CalculateWheelContactPoint(body_transform, *w, r1_plus_u, r2);
+			CalculateWheelContactPoint(*w, r1_plus_u, r2);
 
 			// Suspension spring
 			if (settings->mSuspensionMaxLength > settings->mSuspensionMinLength)
-				w->mSuspensionPart.CalculateConstraintProperties(inDeltaTime, *mBody, r1_plus_u, *w->mContactBody, r2, w->mWSDirection, w->mAntiRollBarImpulse, w->mContactLength - settings->mRadius - settings->mSuspensionMaxLength - settings->mSuspensionPreloadLength, settings->mSuspensionFrequency, settings->mSuspensionDamping);
+				w->mSuspensionPart.CalculateConstraintProperties(inDeltaTime, *mBody, r1_plus_u, *w->mContactBody, r2, w->mWSDirection, w->mAntiRollBarImpulse, w->mSuspensionLength - settings->mSuspensionMaxLength - settings->mSuspensionPreloadLength, settings->mSuspensionFrequency, settings->mSuspensionDamping);
 			else
 				w->mSuspensionPart.Deactivate();
 
 			// Check if we reached the 'max up' position
-			float max_up_error = w->mContactLength - settings->mRadius - settings->mSuspensionMinLength;
+			float max_up_error = w->mSuspensionLength - settings->mSuspensionMinLength;
 			if (max_up_error < 0.0f)
 				w->mSuspensionMaxUpPart.CalculateConstraintProperties(inDeltaTime, *mBody, r1_plus_u, *w->mContactBody, r2, w->mWSDirection, 0.0f, max_up_error);
 			else
@@ -422,7 +420,7 @@ bool VehicleConstraint::SolvePositionConstraint(float inDeltaTime, float inBaumg
 			{
 				// Recalculate constraint properties since the body may have moved
 				Vec3 r1_plus_u, r2;
-				CalculateWheelContactPoint(body_transform, *w, r1_plus_u, r2);
+				CalculateWheelContactPoint(*w, r1_plus_u, r2);
 				w->mSuspensionMaxUpPart.CalculateConstraintProperties(inDeltaTime, *mBody, r1_plus_u, *w->mContactBody, r2, ws_direction, 0.0f, max_up_error);
 
 				impulse |= w->mSuspensionMaxUpPart.SolvePositionConstraint(*mBody, *w->mContactBody, ws_direction, max_up_error, inBaumgarte);

+ 2 - 1
Jolt/Physics/Vehicle/VehicleConstraint.h

@@ -102,6 +102,7 @@ public:
 
 	/// Get the state of a wheel
 	Wheel *						GetWheel(uint inIdx)						{ return mWheels[inIdx]; }
+	const Wheel *				GetWheel(uint inIdx) const					{ return mWheels[inIdx]; }
 
 	/// Get the transform of a wheel in local space to the vehicle body, returns a matrix that transforms a cylinder aligned with the Y axis in body space (not COM space)
 	/// @param inWheelIndex Index of the wheel to fetch
@@ -136,7 +137,7 @@ private:
 	virtual void				OnStep(float inDeltaTime, PhysicsSystem &inPhysicsSystem) override;
 
 	// Calculate the contact positions of the wheel in world space, relative to the center of mass of both bodies
-	void						CalculateWheelContactPoint(RMat44Arg inBodyTransform, const Wheel &inWheel, Vec3 &outR1PlusU, Vec3 &outR2) const;
+	void						CalculateWheelContactPoint(const Wheel &inWheel, Vec3 &outR1PlusU, Vec3 &outR2) const;
 
 	// Calculate the constraint properties for mPitchRollPart
 	void						CalculatePitchRollConstraintProperties(float inDeltaTime, RMat44Arg inBodyTransform);

+ 1 - 1
Jolt/Physics/Vehicle/Wheel.cpp

@@ -51,7 +51,7 @@ void WheelSettings::RestoreBinaryState(StreamIn &inStream)
 
 Wheel::Wheel(const WheelSettings &inSettings) :
 	mSettings(&inSettings),
-	mContactLength(inSettings.mSuspensionMaxLength + inSettings.mRadius)
+	mSuspensionLength(inSettings.mSuspensionMaxLength)
 {
 	JPH_ASSERT(inSettings.mDirection.IsNormalized());
 	JPH_ASSERT(inSettings.mSuspensionMinLength >= 0.0f);

+ 2 - 2
Jolt/Physics/Vehicle/Wheel.h

@@ -93,7 +93,7 @@ public:
 	Vec3					GetContactLateral() const					{ JPH_ASSERT(mContactBody != nullptr); return mContactLateral; }
 
 	/// Get the length of the suspension for a wheel (m) relative to the suspension attachment point (hard point)
-	float					GetSuspensionLength() const					{ return mContactLength - mSettings->mRadius; }
+	float					GetSuspensionLength() const					{ return mSuspensionLength; }
 
 	/// Check if the suspension hit its upper limit
 	bool					HasHitHardPoint() const						{ return mSuspensionMaxUpPart.IsActive(); }
@@ -120,7 +120,7 @@ protected:
 	BodyID					mContactBodyID;								///< ID of body for ground
 	SubShapeID				mContactSubShapeID;							///< Sub shape ID for ground
 	Body *					mContactBody = nullptr;						///< Body for ground
-	float					mContactLength;								///< Length between attachment point and ground
+	float					mSuspensionLength;							///< Current length of the suspension
 	RVec3					mContactPosition;							///< Position of the contact point between wheel and ground
 	Vec3					mContactPointVelocity;						///< Velocity of the contact point (m / s, not relative to the wheel but in world space)
 	Vec3					mContactNormal;								///< Normal of the contact point between wheel and ground

+ 2 - 1
Samples/Tests/Vehicle/VehicleConstraintTest.cpp

@@ -39,6 +39,7 @@ void VehicleConstraintTest::Initialize()
 	// Create collision testers
 	mTesters[0] = new VehicleCollisionTesterRay(Layers::MOVING);
 	mTesters[1] = new VehicleCollisionTesterCastSphere(Layers::MOVING, 0.5f * wheel_width);
+	mTesters[2] = new VehicleCollisionTesterCastCylinder(Layers::MOVING);
 
 	// Create vehicle body
 	RVec3 position(0, 2, 0);
@@ -212,7 +213,7 @@ void VehicleConstraintTest::CreateSettingsMenu(DebugUI *inUI, UIElement *inSubMe
 {
 	VehicleTest::CreateSettingsMenu(inUI, inSubMenu);
 
-	inUI->CreateComboBox(inSubMenu, "Collision Mode", { "Ray", "Cast Sphere" }, sCollisionMode, [](int inItem) { sCollisionMode = inItem; });
+	inUI->CreateComboBox(inSubMenu, "Collision Mode", { "Ray", "Cast Sphere", "Cast Cylinder" }, sCollisionMode, [](int inItem) { sCollisionMode = inItem; });
 	inUI->CreateCheckBox(inSubMenu, "4 Wheel Drive", sFourWheelDrive, [this](UICheckBox::EState inState) { sFourWheelDrive = inState == UICheckBox::STATE_CHECKED; RestartTest(); });
 	inUI->CreateCheckBox(inSubMenu, "Anti Rollbars", sAntiRollbar, [this](UICheckBox::EState inState) { sAntiRollbar = inState == UICheckBox::STATE_CHECKED; RestartTest(); });
 	inUI->CreateCheckBox(inSubMenu, "Limited Slip Differentials", sLimitedSlipDifferentials, [](UICheckBox::EState inState) { sLimitedSlipDifferentials = inState == UICheckBox::STATE_CHECKED; });

+ 2 - 2
Samples/Tests/Vehicle/VehicleConstraintTest.h

@@ -26,7 +26,7 @@ public:
 	virtual void				CreateSettingsMenu(DebugUI *inUI, UIElement *inSubMenu) override;
 
 private:
-	static inline int			sCollisionMode = 1;
+	static inline int			sCollisionMode = 2;
 	static inline bool			sFourWheelDrive = false;
 	static inline bool			sAntiRollbar = true;
 	static inline bool			sLimitedSlipDifferentials = true;
@@ -35,6 +35,6 @@ private:
 
 	Body *						mCarBody;									///< The vehicle
 	Ref<VehicleConstraint>		mVehicleConstraint;							///< The vehicle constraint
-	Ref<VehicleCollisionTester>	mTesters[2];								///< Collision testers for the wheel
+	Ref<VehicleCollisionTester>	mTesters[3];								///< Collision testers for the wheel
 	float						mPreviousForward = 1.0f;					///< Keeps track of last car direction so we know when to brake and when to accelerate
 };