Jelajahi Sumber

Experimental motorcycle physics support (#489)

Note that this is work in progress, the bike is still likely to spin out so it will require a lot of tweaking to incorporate this into a game. It is also likely that API changes will be needed in the future.
Jorrit Rouwe 2 tahun lalu
induk
melakukan
7e84112694

+ 2 - 0
Jolt/Jolt.cmake

@@ -361,6 +361,8 @@ set(JOLT_PHYSICS_SRC_FILES
 	${JOLT_PHYSICS_ROOT}/Physics/StateRecorder.h
 	${JOLT_PHYSICS_ROOT}/Physics/StateRecorderImpl.cpp
 	${JOLT_PHYSICS_ROOT}/Physics/StateRecorderImpl.h
+	${JOLT_PHYSICS_ROOT}/Physics/Vehicle/MotorcycleController.cpp
+	${JOLT_PHYSICS_ROOT}/Physics/Vehicle/MotorcycleController.h
 	${JOLT_PHYSICS_ROOT}/Physics/Vehicle/TrackedVehicleController.cpp
 	${JOLT_PHYSICS_ROOT}/Physics/Vehicle/TrackedVehicleController.h
 	${JOLT_PHYSICS_ROOT}/Physics/Vehicle/VehicleAntiRollBar.cpp

+ 235 - 0
Jolt/Physics/Vehicle/MotorcycleController.cpp

@@ -0,0 +1,235 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2023 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#include <Jolt/Jolt.h>
+
+#include <Jolt/Physics/Vehicle/MotorcycleController.h>
+#include <Jolt/Physics/PhysicsSystem.h>
+#include <Jolt/ObjectStream/TypeDeclarations.h>
+#include <Jolt/Core/StreamIn.h>
+#include <Jolt/Core/StreamOut.h>
+#ifdef JPH_DEBUG_RENDERER
+	#include <Jolt/Renderer/DebugRenderer.h>
+#endif // JPH_DEBUG_RENDERER
+
+JPH_NAMESPACE_BEGIN
+
+JPH_IMPLEMENT_SERIALIZABLE_VIRTUAL(MotorcycleControllerSettings)
+{
+	JPH_ADD_BASE_CLASS(MotorcycleControllerSettings, VehicleControllerSettings)
+
+	JPH_ADD_ATTRIBUTE(MotorcycleControllerSettings, mMaxLeanAngle)
+	JPH_ADD_ATTRIBUTE(MotorcycleControllerSettings, mLeanSpringConstant)
+	JPH_ADD_ATTRIBUTE(MotorcycleControllerSettings, mLeanSpringDamping)
+	JPH_ADD_ATTRIBUTE(MotorcycleControllerSettings, mLeanSmoothingFactor)
+}
+
+VehicleController *MotorcycleControllerSettings::ConstructController(VehicleConstraint &inConstraint) const
+{
+	return new MotorcycleController(*this, inConstraint);
+}
+
+void MotorcycleControllerSettings::SaveBinaryState(StreamOut &inStream) const
+{
+	WheeledVehicleControllerSettings::SaveBinaryState(inStream);
+
+	inStream.Write(mMaxLeanAngle);
+	inStream.Write(mLeanSpringConstant);
+	inStream.Write(mLeanSpringDamping);
+	inStream.Write(mLeanSmoothingFactor);
+}
+
+void MotorcycleControllerSettings::RestoreBinaryState(StreamIn &inStream)
+{
+	WheeledVehicleControllerSettings::RestoreBinaryState(inStream);
+
+	inStream.Read(mMaxLeanAngle);
+	inStream.Read(mLeanSpringConstant);
+	inStream.Read(mLeanSpringDamping);
+	inStream.Read(mLeanSmoothingFactor);
+}
+
+MotorcycleController::MotorcycleController(const MotorcycleControllerSettings &inSettings, VehicleConstraint &inConstraint) :
+	WheeledVehicleController(inSettings, inConstraint),
+	mMaxLeanAngle(inSettings.mMaxLeanAngle),
+	mLeanSpringConstant(inSettings.mLeanSpringConstant),
+	mLeanSpringDamping(inSettings.mLeanSpringDamping),
+	mLeanSmoothingFactor(inSettings.mLeanSmoothingFactor)
+{
+}
+
+float MotorcycleController::GetWheelBase() const
+{
+	float low = FLT_MAX, high = -FLT_MAX;
+
+	for (const Wheel *w : mConstraint.GetWheels())
+	{
+		const WheelSettings *s = w->GetSettings();
+
+		// Measure distance along the forward axis by looking at the fully extended suspension
+		float value = (s->mPosition + s->mSuspensionDirection * s->mSuspensionMaxLength).Dot(mConstraint.GetLocalForward());
+
+		// Update min and max
+		low = min(low, value);
+		high = max(high, value);
+	}
+
+	return high - low;
+}
+
+void MotorcycleController::PreCollide(float inDeltaTime, PhysicsSystem &inPhysicsSystem)
+{
+	WheeledVehicleController::PreCollide(inDeltaTime, inPhysicsSystem);
+
+	Vec3 gravity = inPhysicsSystem.GetGravity();
+	float gravity_len = gravity.Length();
+	Vec3 world_up = gravity_len > 0.0f? -gravity / gravity_len : mConstraint.GetLocalUp();
+
+	Body *body = mConstraint.GetVehicleBody();
+	Vec3 forward = body->GetRotation() * mConstraint.GetLocalForward();
+	float wheel_base = GetWheelBase();
+	float velocity = body->GetLinearVelocity().Dot(forward);
+	float velocity_sq = Square(velocity);
+
+	// Calculate the target lean vector, this is in the direction of the total applied impulse by the ground on the wheels
+	Vec3 target_lean = Vec3::sZero();
+	for (const Wheel *w : mConstraint.GetWheels())
+		if (w->HasContact())
+			target_lean += w->GetContactNormal() * w->GetSuspensionLambda() + w->GetContactLateral() * w->GetLateralLambda();
+
+	// Normalize the impulse
+	target_lean = target_lean.NormalizedOr(world_up);
+
+	// Smooth the impulse to avoid jittery behavior
+	mTargetLean = mLeanSmoothingFactor * mTargetLean + (1.0f - mLeanSmoothingFactor) * target_lean;
+
+	// Remove forward component, we can only lean sideways
+	mTargetLean -= mTargetLean * mTargetLean.Dot(forward);
+	mTargetLean = mTargetLean.NormalizedOr(world_up);
+
+	// Calculate max steering angle based on the max lean angle we're willing to take
+	// See: https://en.wikipedia.org/wiki/Bicycle_and_motorcycle_dynamics#Leaning
+	// LeanAngle = Atan(Velocity^2 / (Gravity * TurnRadius))
+	// And: https://en.wikipedia.org/wiki/Turning_radius (we're ignoring the tire width)
+	// The CasterAngle is the added according to https://en.wikipedia.org/wiki/Bicycle_and_motorcycle_dynamics#Turning (this is the same formula but without small angle approximation)
+	// TurnRadius = WheelBase / (Sin(SteerAngle) * Cos(CasterAngle))
+	// => SteerAngle = ASin(WheelBase * Tan(LeanAngle) * Gravity / (Velocity^2 * Cos(CasterAngle))
+	// The caster angle is different for each wheel so we can only calculate part of the equation here
+	float max_steer_angle_factor = wheel_base * Tan(mMaxLeanAngle) * gravity_len;
+
+	// Decompose steering into sign and direction
+	float steer_strength = abs(mRightInput);
+	float steer_sign = -Sign(mRightInput);
+
+	for (Wheel *w_base : mConstraint.GetWheels())
+	{
+		WheelWV *w = static_cast<WheelWV *>(w_base);
+		const WheelSettingsWV *s = w->GetSettings();
+
+		// Check if this wheel can steer
+		if (s->mMaxSteerAngle != 0.0f)
+		{
+			// Calculate cos(caster angle), the angle between the steering axis and the up vector
+			float cos_caster_angle = s->mSteeringAxis.Dot(mConstraint.GetLocalUp());
+
+			// Calculate steer angle
+			float steer_angle = steer_strength * w->GetSettings()->mMaxSteerAngle;
+
+			// Clamp to max steering angle
+			if (velocity_sq > 1.0e-6f)
+			{
+				float max_steer_angle = ASin(max_steer_angle_factor / (velocity_sq * cos_caster_angle));
+				steer_angle = min(steer_angle, max_steer_angle);
+			}
+
+			// Set steering angle
+			w->SetSteerAngle(steer_sign * steer_angle);
+		}
+	}
+
+	// Reset applied impulse
+	mAppliedImpulse = 0;
+}
+
+bool MotorcycleController::SolveLongitudinalAndLateralConstraints(float inDeltaTime) 
+{
+	bool impulse = WheeledVehicleController::SolveLongitudinalAndLateralConstraints(inDeltaTime);
+
+	// Only apply a lean impulse if all wheels are in contact, otherwise we can easily spin out
+	bool all_in_contact = true;
+	for (Wheel *w : mConstraint.GetWheels())
+		if (!w->HasContact() || w->GetSuspensionLambda() <= 0.0f)
+		{
+			all_in_contact = false;
+			break;
+		}
+
+	if (all_in_contact)
+	{
+		Body *body = mConstraint.GetVehicleBody();
+		MotionProperties *mp = body->GetMotionProperties();
+
+		Vec3 forward = body->GetRotation() * mConstraint.GetLocalForward();
+		Vec3 up = body->GetRotation() * mConstraint.GetLocalUp();
+
+		// Calculate delta to target angle and derivative
+		float d_angle = -Sign(mTargetLean.Cross(up).Dot(forward)) * ACos(mTargetLean.Dot(up));
+		float ddt_angle = body->GetAngularVelocity().Dot(forward);
+
+		// Calculate impulse to apply to get to target lean angle
+		float total_impulse = (mLeanSpringConstant * d_angle - mLeanSpringDamping * ddt_angle) * inDeltaTime;
+
+		// Remember angular velocity pre angular impulse
+		Vec3 old_w = mp->GetAngularVelocity();
+
+		// Apply impulse taking into account the impulse we've applied earlier
+		float delta_impulse = total_impulse - mAppliedImpulse;
+		body->AddAngularImpulse(delta_impulse * forward);
+		mAppliedImpulse = total_impulse;
+
+		// Calculate delta angular velocity due to angular impulse
+		Vec3 dw = mp->GetAngularVelocity() - old_w;
+		Vec3 linear_acceleration = Vec3::sZero();
+		float total_lambda = 0.0f;
+		for (Wheel *w_base : mConstraint.GetWheels())
+		{
+			WheelWV *w = static_cast<WheelWV *>(w_base);
+
+			// We weigh the importance of each contact point according to the contact force
+			float lambda = w->GetSuspensionLambda();
+			total_lambda += lambda;
+
+			// Linear acceleration of contact point is dw x com_to_contact
+			Vec3 r = Vec3(w->GetContactPosition() - body->GetCenterOfMassPosition());
+			linear_acceleration += lambda * dw.Cross(r);
+		}
+
+		// Apply linear impulse to COM to cancel the average velocity change on the wheels due to the angular impulse
+		Vec3 linear_impulse = -linear_acceleration / (total_lambda * mp->GetInverseMass());
+		body->AddImpulse(linear_impulse);
+
+		// Return true if we applied an impulse
+		impulse |= delta_impulse != 0.0f;
+	}
+
+	return impulse;
+}
+
+#ifdef JPH_DEBUG_RENDERER
+
+void MotorcycleController::Draw(DebugRenderer *inRenderer) const 
+{
+	WheeledVehicleController::Draw(inRenderer);
+
+	// Draw current and desired lean angle
+	Body *body = mConstraint.GetVehicleBody();
+	RVec3 center_of_mass = body->GetCenterOfMassPosition();
+	Vec3 up = body->GetRotation() * mConstraint.GetLocalUp();
+	inRenderer->DrawArrow(center_of_mass, center_of_mass + up, Color::sYellow, 0.1f);
+	inRenderer->DrawArrow(center_of_mass, center_of_mass + mTargetLean, Color::sRed, 0.1f);
+}
+
+#endif // JPH_DEBUG_RENDERER
+
+JPH_NAMESPACE_END

+ 70 - 0
Jolt/Physics/Vehicle/MotorcycleController.h

@@ -0,0 +1,70 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2023 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#pragma once
+
+#include <Jolt/Physics/Vehicle/WheeledVehicleController.h>
+
+JPH_NAMESPACE_BEGIN
+
+/// Settings of a two wheeled motorcycle (adds a spring to balance the motorcycle)
+/// Note: The motor cycle controller is still in development and may need a lot of tweaks/hacks to work properly!
+class MotorcycleControllerSettings : public WheeledVehicleControllerSettings
+{
+public:
+	JPH_DECLARE_SERIALIZABLE_VIRTUAL(MotorcycleControllerSettings)
+
+	// See: VehicleControllerSettings
+	virtual VehicleController *	ConstructController(VehicleConstraint &inConstraint) const override;
+	virtual void				SaveBinaryState(StreamOut &inStream) const override;
+	virtual void				RestoreBinaryState(StreamIn &inStream) override;
+
+	/// How far we're willing to make the bike lean over in turns (in radians)
+	float						mMaxLeanAngle = DegreesToRadians(45.0f);
+
+	/// Spring constant for the lean spring
+	float						mLeanSpringConstant = 5000.0f;
+
+	/// Spring damping constant for the lean spring
+	float						mLeanSpringDamping = 1000.0f;
+
+	/// How much to smooth the lean angle (0 = no smoothing, 1 = lean angle never changes)
+	/// Note that this is frame rate dependent because the formula is: smoothing_factor * previous + (1 - smoothing_factor) * current
+	float						mLeanSmoothingFactor = 0.8f;
+};
+
+/// Runtime controller class
+class MotorcycleController : public WheeledVehicleController
+{
+public:
+	JPH_OVERRIDE_NEW_DELETE
+
+	/// Constructor
+								MotorcycleController(const MotorcycleControllerSettings &inSettings, VehicleConstraint &inConstraint);
+
+	/// Get the distance between the front and back wheels
+	float						GetWheelBase() const;
+
+protected:
+	// See: VehicleController
+	virtual void				PreCollide(float inDeltaTime, PhysicsSystem &inPhysicsSystem) override;
+	virtual bool				SolveLongitudinalAndLateralConstraints(float inDeltaTime) override;
+#ifdef JPH_DEBUG_RENDERER
+	virtual void				Draw(DebugRenderer *inRenderer) const override;
+#endif // JPH_DEBUG_RENDERER
+
+	// Configuration properties
+	float						mMaxLeanAngle;
+	float						mLeanSpringConstant;
+	float						mLeanSpringDamping;
+	float						mLeanSmoothingFactor;
+
+	// Run-time calculated target lean vector
+	Vec3						mTargetLean = Vec3::sZero();
+
+	// Run-time total angular impulse applied to turn the cycle towards the target lean angle
+	float						mAppliedImpulse = 0.0f;
+};
+
+JPH_NAMESPACE_END

+ 1 - 1
Jolt/Physics/Vehicle/VehicleCollisionTester.h

@@ -89,7 +89,7 @@ public:
 	/// 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) { }
+								VehicleCollisionTesterCastCylinder(ObjectLayer inObjectLayer, float inConvexRadiusFraction = 0.1f) : mObjectLayer(inObjectLayer), mConvexRadiusFraction(inConvexRadiusFraction) { JPH_ASSERT(mConvexRadiusFraction >= 0.0f && mConvexRadiusFraction <= 1.0f); }
 
 	// 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;

+ 2 - 0
Samples/Samples.cmake

@@ -205,6 +205,8 @@ set(SAMPLES_SRC_FILES
 	${SAMPLES_ROOT}/Tests/Shapes/TaperedCapsuleShapeTest.h
 	${SAMPLES_ROOT}/Tests/Shapes/TriangleShapeTest.cpp
 	${SAMPLES_ROOT}/Tests/Shapes/TriangleShapeTest.h
+	${SAMPLES_ROOT}/Tests/Vehicle/MotorcycleTest.cpp
+	${SAMPLES_ROOT}/Tests/Vehicle/MotorcycleTest.h
 	${SAMPLES_ROOT}/Tests/Vehicle/TankTest.cpp
 	${SAMPLES_ROOT}/Tests/Vehicle/TankTest.h
 	${SAMPLES_ROOT}/Tests/Vehicle/VehicleConstraintTest.cpp

+ 2 - 0
Samples/SamplesApp.cpp

@@ -273,11 +273,13 @@ static TestNameAndRTTI sWaterTests[] =
 
 JPH_DECLARE_RTTI_FOR_FACTORY(VehicleSixDOFTest)
 JPH_DECLARE_RTTI_FOR_FACTORY(VehicleConstraintTest)
+JPH_DECLARE_RTTI_FOR_FACTORY(MotorcycleTest)
 JPH_DECLARE_RTTI_FOR_FACTORY(TankTest)
 
 static TestNameAndRTTI sVehicleTests[] =
 {
 	{ "Car (VehicleConstraint)",			JPH_RTTI(VehicleConstraintTest) },
+	{ "Motorcycle (VehicleConstraint)",		JPH_RTTI(MotorcycleTest) },
 	{ "Tank (VehicleConstraint)",			JPH_RTTI(TankTest) },
 	{ "Car (SixDOFConstraint)",				JPH_RTTI(VehicleSixDOFTest) },
 };

+ 207 - 0
Samples/Tests/Vehicle/MotorcycleTest.cpp

@@ -0,0 +1,207 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2023 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#include <TestFramework.h>
+
+#include <Tests/Vehicle/MotorcycleTest.h>
+#include <Jolt/Physics/Collision/Shape/BoxShape.h>
+#include <Jolt/Physics/Collision/Shape/OffsetCenterOfMassShape.h>
+#include <Jolt/Physics/Vehicle/MotorcycleController.h>
+#include <Jolt/Physics/Body/BodyCreationSettings.h>
+#include <Layers.h>
+#include <Renderer/DebugRendererImp.h>
+
+JPH_IMPLEMENT_RTTI_VIRTUAL(MotorcycleTest) 
+{ 
+	JPH_ADD_BASE_CLASS(MotorcycleTest, VehicleTest) 
+}
+
+MotorcycleTest::~MotorcycleTest()
+{
+	mPhysicsSystem->RemoveStepListener(mVehicleConstraint);
+}
+
+void MotorcycleTest::Initialize()
+{
+	VehicleTest::Initialize();
+
+	// Loosly based on: https://www.whitedogbikes.com/whitedogblog/yamaha-xj-900-specs/
+	const float back_wheel_radius = 0.31f;
+	const float back_wheel_width = 0.05f;
+	const float back_wheel_pos_z = -0.75f;
+	const float back_suspension_min_length = 0.3f;
+	const float back_suspension_max_length = 0.5f;
+	const float back_suspension_freq = 2.0f;
+	const float back_brake_torque = 250.0f;
+
+	const float front_wheel_radius = 0.31f;
+	const float front_wheel_width = 0.05f;
+	const float front_wheel_pos_z = 0.75f;
+	const float front_suspension_min_length = 0.3f;
+	const float front_suspension_max_length = 0.5f;
+	const float front_suspension_freq = 1.5f;
+	const float front_brake_torque = 500.0f;
+
+	const float half_vehicle_length = 0.4f;
+	const float half_vehicle_width = 0.2f;
+	const float half_vehicle_height = 0.3f;
+
+	const float max_steering_angle = DegreesToRadians(30);
+
+	// Angle of the front suspension
+	const float caster_angle = DegreesToRadians(30);
+
+	// Create vehicle body
+	RVec3 position(0, 2, 0);
+	RefConst<Shape> motorcycle_shape = OffsetCenterOfMassShapeSettings(Vec3(0, -half_vehicle_height, 0), new BoxShape(Vec3(half_vehicle_width, half_vehicle_height, half_vehicle_length))).Create().Get();
+	BodyCreationSettings motorcycle_body_settings(motorcycle_shape, position, Quat::sIdentity(), EMotionType::Dynamic, Layers::MOVING);
+	motorcycle_body_settings.mOverrideMassProperties = EOverrideMassProperties::CalculateInertia;
+	motorcycle_body_settings.mMassPropertiesOverride.mMass = 240.0f;
+	mMotorcycleBody = mBodyInterface->CreateBody(motorcycle_body_settings);
+	mBodyInterface->AddBody(mMotorcycleBody->GetID(), EActivation::Activate);
+
+	// Create vehicle constraint
+	VehicleConstraintSettings vehicle;
+	vehicle.mDrawConstraintSize = 0.1f;
+	vehicle.mMaxPitchRollAngle = DegreesToRadians(60.0f);
+
+	// Wheels
+	WheelSettingsWV *front = new WheelSettingsWV;
+	front->mPosition = Vec3(0.0f, -0.9f * half_vehicle_height, front_wheel_pos_z);
+	front->mMaxSteerAngle = max_steering_angle;
+	front->mSuspensionDirection = Vec3(0, -1, Tan(caster_angle)).Normalized();
+	front->mSteeringAxis = -front->mSuspensionDirection;
+	front->mRadius = front_wheel_radius;
+	front->mWidth = front_wheel_width;
+	front->mSuspensionMinLength = front_suspension_min_length;
+	front->mSuspensionMaxLength = front_suspension_max_length;
+	front->mSuspensionFrequency = front_suspension_freq;
+	front->mMaxBrakeTorque = front_brake_torque;
+
+	WheelSettingsWV *back = new WheelSettingsWV;
+	back->mPosition = Vec3(0.0f, -0.9f * half_vehicle_height, back_wheel_pos_z);
+	back->mMaxSteerAngle = 0.0f;
+	back->mRadius = back_wheel_radius;
+	back->mWidth = back_wheel_width;
+	back->mSuspensionMinLength = back_suspension_min_length;
+	back->mSuspensionMaxLength = back_suspension_max_length;
+	back->mSuspensionFrequency = back_suspension_freq;
+	back->mMaxBrakeTorque = back_brake_torque;
+
+	vehicle.mWheels = { front, back };
+
+	MotorcycleControllerSettings *controller = new MotorcycleControllerSettings;
+	controller->mEngine.mMaxTorque = 80.0f;
+	controller->mEngine.mMinRPM = 1000.0f;
+	controller->mEngine.mMaxRPM = 10000.0f;
+	controller->mTransmission.mShiftDownRPM = 2000.0f;
+	controller->mTransmission.mShiftUpRPM = 9000.0f;
+	controller->mTransmission.mGearRatios = { 2.27f, 1.63f, 1.3f, 1.09f, 0.96f, 0.88f }; // From: https://www.blocklayer.com/rpm-gear-bikes
+	controller->mTransmission.mReverseGearRatios = { -4.0f };
+	vehicle.mController = controller;
+
+	// Differential (not really applicable to a motorcycle but we need one anyway to drive it)
+	controller->mDifferentials.resize(1);
+	controller->mDifferentials[0].mLeftWheel = -1;
+	controller->mDifferentials[0].mRightWheel = 1;
+	controller->mDifferentials[0].mDifferentialRatio = 1.93f * 40.0f / 16.0f; // Combining primary and final drive (back divided by front sprockets) from: https://www.blocklayer.com/rpm-gear-bikes
+
+	mVehicleConstraint = new VehicleConstraint(*mMotorcycleBody, vehicle);
+	mVehicleConstraint->SetVehicleCollisionTester(new VehicleCollisionTesterCastCylinder(Layers::MOVING, 1.0f)); // Use half wheel width as convex radius so we get a rounded cyclinder
+	mPhysicsSystem->AddConstraint(mVehicleConstraint);
+	mPhysicsSystem->AddStepListener(mVehicleConstraint);
+}
+
+void MotorcycleTest::PrePhysicsUpdate(const PreUpdateParams &inParams)
+{
+	VehicleTest::PrePhysicsUpdate(inParams);
+
+	// Determine acceleration and brake
+	float forward = 0.0f, right = 0.0f, brake = 0.0f;
+	if (inParams.mKeyboard->IsKeyPressed(DIK_Z))
+		brake = 1.0f;
+	else if (inParams.mKeyboard->IsKeyPressed(DIK_UP))
+		forward = 1.0f;
+	else if (inParams.mKeyboard->IsKeyPressed(DIK_DOWN))		
+		forward = -1.0f;
+
+	// Check if we're reversing direction
+	if (mPreviousForward * forward < 0.0f)
+	{
+		// Get vehicle velocity in local space to the body of the vehicle
+		float velocity = (mMotorcycleBody->GetRotation().Conjugated() * mMotorcycleBody->GetLinearVelocity()).GetZ();
+		if ((forward > 0.0f && velocity < -0.1f) || (forward < 0.0f && velocity > 0.1f))
+		{
+			// Brake while we've not stopped yet
+			forward = 0.0f;
+			brake = 1.0f;
+		}
+		else
+		{
+			// When we've come to a stop, accept the new direction
+			mPreviousForward = forward;
+		}
+	}
+
+	// Steering
+	if (inParams.mKeyboard->IsKeyPressed(DIK_LEFT))
+		right = -1.0f;
+	else if (inParams.mKeyboard->IsKeyPressed(DIK_RIGHT))
+		right = 1.0f;
+	const float steer_speed = 4.0f;
+	if (right > mCurrentRight)
+		mCurrentRight = min(mCurrentRight + steer_speed * inParams.mDeltaTime, right);
+	else if (right < mCurrentRight)
+		mCurrentRight = max(mCurrentRight - steer_speed * inParams.mDeltaTime, right);
+
+	// When leaned, we don't want to use the brakes fully as we'll spin out
+	if (brake > 0.0f)
+	{
+		Vec3 world_up = -mPhysicsSystem->GetGravity().Normalized();
+		Vec3 up = mMotorcycleBody->GetRotation() * mVehicleConstraint->GetLocalUp();
+		Vec3 fwd = mMotorcycleBody->GetRotation() * mVehicleConstraint->GetLocalForward();
+		float sin_lean_angle = abs(world_up.Cross(up).Dot(fwd));
+		float brake_multiplier = Square(1.0f - sin_lean_angle);
+		brake *= brake_multiplier;
+	}
+
+	// On user input, assure that the motorcycle is active
+	if (mCurrentRight != 0.0f || forward != 0.0f || brake != 0.0f)
+		mBodyInterface->ActivateBody(mMotorcycleBody->GetID());
+
+	// Pass the input on to the constraint
+	WheeledVehicleController *controller = static_cast<WheeledVehicleController *>(mVehicleConstraint->GetController());
+	controller->SetDriverInput(forward, mCurrentRight, brake, false);
+
+	// Draw our wheels (this needs to be done in the pre update since we draw the bodies too in the state before the step)
+	for (uint w = 0; w < 2; ++w)
+	{
+		const WheelSettings *settings = mVehicleConstraint->GetWheels()[w]->GetSettings();
+		RMat44 wheel_transform = mVehicleConstraint->GetWheelWorldTransform(w, Vec3::sAxisY(), Vec3::sAxisX()); // The cyclinder we draw is aligned with Y so we specify that as rotational axis
+		mDebugRenderer->DrawCylinder(wheel_transform, 0.5f * settings->mWidth, settings->mRadius, Color::sGreen);
+	}
+}
+
+void MotorcycleTest::GetInitialCamera(CameraState &ioState) const 
+{
+	// Position camera behind motorcycle
+	RVec3 cam_tgt = RVec3(0, 0, 5);
+	ioState.mPos = RVec3(0, 2.5f, -5);
+	ioState.mForward = Vec3(cam_tgt - ioState.mPos).Normalized();
+}
+
+RMat44 MotorcycleTest::GetCameraPivot(float inCameraHeading, float inCameraPitch) const 
+{
+	// Pivot is center of motorcycle and rotates with motorcycle around Y axis only
+	Vec3 fwd = mMotorcycleBody->GetRotation().RotateAxisZ();
+	fwd.SetY(0.0f);
+	float len = fwd.Length();
+	if (len != 0.0f)
+		fwd /= len;
+	else
+		fwd = Vec3::sAxisZ();
+	Vec3 up = Vec3::sAxisY();
+	Vec3 right = up.Cross(fwd);
+	return RMat44(Vec4(right, 0), Vec4(up, 0), Vec4(fwd, 0), mMotorcycleBody->GetPosition());
+}

+ 32 - 0
Samples/Tests/Vehicle/MotorcycleTest.h

@@ -0,0 +1,32 @@
+// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)
+// SPDX-FileCopyrightText: 2023 Jorrit Rouwe
+// SPDX-License-Identifier: MIT
+
+#pragma once
+
+#include <Tests/Vehicle/VehicleTest.h>
+#include <Jolt/Physics/Vehicle/VehicleConstraint.h>
+
+// This test shows how a motorcycle could be made with the vehicle constraint.
+/// Note: The motor cycle controller is still in development and may need a lot of tweaks/hacks to work properly!
+class MotorcycleTest : public VehicleTest
+{
+public:
+	JPH_DECLARE_RTTI_VIRTUAL(MotorcycleTest)
+
+	// Destructor
+	virtual						~MotorcycleTest() override;
+
+	// See: Test
+	virtual void				Initialize() override;
+	virtual void				PrePhysicsUpdate(const PreUpdateParams &inParams) override;
+
+	virtual void				GetInitialCamera(CameraState &ioState) const override;
+	virtual RMat44				GetCameraPivot(float inCameraHeading, float inCameraPitch) const override;
+
+private:
+	Body *						mMotorcycleBody;							///< The vehicle
+	Ref<VehicleConstraint>		mVehicleConstraint;							///< The vehicle constraint
+	float						mPreviousForward = 1.0f;					///< Keeps track of last motorcycle direction so we know when to brake and when to accelerate
+	float						mCurrentRight = 0.0f;						///< Keeps track of the current steering angle (radians)
+};