first commit

This commit is contained in:
Valera
2025-06-11 20:19:35 +07:00
commit 35790cbd34
107 changed files with 3400 additions and 0 deletions

View File

@@ -0,0 +1,11 @@
using Sandbox;
namespace VeloX;
public abstract partial class VeloXBase
{
//[Property, Feature( "Input" ), InputAction] string ThrottleInput { get; set; } = "Forward";
[Property, Feature( "Input" )] internal InputResolver Input { get; set; } = new();
[Property, Feature( "Input" )] public GameObject Driver { get => Input.Driver; set => Input.Driver = value; }
}

View File

@@ -0,0 +1,43 @@
using Sandbox;
namespace VeloX;
public abstract partial class VeloXBase
{
private Vector3 linForce;
private Vector3 angForce;
private void PhysicsSimulate()
{
var drag = AngularDrag;
var mass = Body.Mass;
var angVel = Body.AngularVelocity;
linForce.x = 0;
linForce.y = 0;
linForce.z = 0;
angForce.x = angVel.x * drag.x * mass;
angForce.y = angVel.y * drag.y * mass;
angForce.z = angVel.z * drag.z * mass;
if ( Wheels.Count > 0 )
{
Vector3 vehVel = Body.Velocity;
Vector3 vehAngVel = Body.AngularVelocity;
var dt = Time.Delta;
foreach ( var v in Wheels )
v.DoPhysics( this, ref vehVel, ref vehAngVel, ref linForce, ref angForce, in dt );
Body.Velocity = vehVel;
Body.AngularVelocity = vehAngVel;
}
Body.ApplyForce( linForce );
Body.ApplyTorque( angForce );
}
}

View File

@@ -0,0 +1,62 @@
using Sandbox;
using Sandbox.Audio;
using System;
using System.Text.Json.Serialization;
using VeloX.Audio;
using static Sandbox.Utility.Noise;
using static VeloX.EngineStream;
namespace VeloX;
public abstract partial class VeloXBase : Component, Component.ICollisionListener
{
[Property, Feature( "Effects" ), Group( "Sound" )]
public SoundEvent SuspensionHeavySound { get; protected set; } = ResourceLibrary.Get<SoundEvent>( "sounds/suspension/compress_heavy.sound" );
[Property, Feature( "Effects" ), Group( "Sound" )]
public SoundEvent SuspensionDownSound { get; protected set; } = ResourceLibrary.Get<SoundEvent>( "sounds/suspension/pneumatic_down.sound" );
[Property, Feature( "Effects" ), Group( "Sound" )]
public SoundEvent SuspensionUpSound { get; protected set; } = ResourceLibrary.Get<SoundEvent>( "sounds/suspension/pneumatic_up.sound" );
[Property, Feature( "Effects" ), Group( "Sound" )]
public SoundEvent SoftCollisionSound { get; protected set; } = ResourceLibrary.Get<SoundEvent>( "sounds/collisions/car_light.sound" );
[Property, Feature( "Effects" ), Group( "Sound" )]
public SoundEvent HardCollisionSound { get; protected set; } = ResourceLibrary.Get<SoundEvent>( "sounds/collisions/car_heavy.sound" );
[Property, Feature( "Effects" ), Group( "Sound" )]
public SoundEvent VehicleScrapeSound { get; protected set; } = ResourceLibrary.Get<SoundEvent>( "sounds/collisions/metal_scrape.sound" );
[Property, Feature( "Effects" ), Group( "Particle" )]
public GameObject MetalImpactEffect { get; protected set; } = GameObject.GetPrefab( "effects/metal_impact.prefab" );
void ICollisionListener.OnCollisionStart( Collision collision )
{
var speed = MathF.Abs( collision.Contact.NormalSpeed );
var surfaceNormal = collision.Contact.Normal;
if ( speed < 100 )
return;
var isHardHit = speed > 300;
var volume = Math.Clamp( speed / 400f, 0, 1 );
var sound = Sound.Play( SoftCollisionSound, WorldPosition );
sound.Volume = volume;
var a = MetalImpactEffect.Clone( new CloneConfig() { StartEnabled = true, Transform = new( collision.Contact.Point, surfaceNormal.Cross( surfaceNormal ).EulerAngles ) } );
a.Components.Get<ParticleConeEmitter>().Burst = speed / 2;
if ( isHardHit )
{
var hardSound = Sound.Play( HardCollisionSound, WorldPosition );
hardSound.Volume = volume;
}
else if ( surfaceNormal.Dot( -collision.Contact.Speed.Normal ) < 0.5f )
{
var scrapSound = Sound.Play( VehicleScrapeSound, WorldPosition );
scrapSound.Volume = 0.4f;
}
}
}

View File

@@ -0,0 +1,20 @@
using Sandbox;
using System.Collections.Generic;
namespace VeloX;
public abstract partial class VeloXBase
{
[Property] public List<VeloXWheel> Wheels { get; set; }
[Property] public TagSet WheelIgnoredTags { get; set; }
public List<VeloXWheel> FindWheels() => [.. Components.GetAll<VeloXWheel>()];
[Button]
public void SetupWheels()
{
Wheels = FindWheels();
}
}

38
Code/Base/VeloXBase.cs Normal file
View File

@@ -0,0 +1,38 @@
using Sandbox;
namespace VeloX;
public abstract partial class VeloXBase : Component
{
[Sync] public EngineState EngineState { get; set; }
[Sync] public WaterState WaterState { get; set; }
[Sync] public bool IsEngineOnFire { get; set; }
[Sync, Range( 0, 1 ), Property] public float Brake { get; set; }
[Sync( SyncFlags.Interpolate ), Range( 0, 1 ), Property] public float Throttle { get; set; }
[Property] public Vector3 AngularDrag { get; set; } = new( -0.1f, -0.1f, -3 );
[Property] public float Mass { get; set; } = 900;
[Property, Group( "Components" )] public Rigidbody Body { get; protected set; }
[Property, Group( "Components" )] public Collider Collider { get; protected set; }
[Sync] public Angles SteerAngle { get; set; }
public Vector3 LocalVelocity;
public float ForwardSpeed;
public float TotalSpeed;
protected override void OnFixedUpdate()
{
if ( IsProxy )
return;
LocalVelocity = WorldTransform.PointToLocal( WorldPosition + Body.Velocity );
ForwardSpeed = LocalVelocity.x;
TotalSpeed = LocalVelocity.Length;
Body.PhysicsBody.Mass = Mass;
PhysicsSimulate();
}
}

View File

@@ -0,0 +1,74 @@
using Sandbox;
namespace VeloX;
public partial class VeloXWheel : Component
{
protected override void DrawGizmos()
{
if ( !Gizmo.IsSelected )
return;
Gizmo.Draw.IgnoreDepth = true;
//
// Suspension length
//
{
var suspensionStart = Vector3.Zero;
var suspensionEnd = Vector3.Zero + Vector3.Down * SuspensionLength;
Gizmo.Draw.Color = Color.Cyan;
Gizmo.Draw.LineThickness = 0.25f;
Gizmo.Draw.Line( suspensionStart, suspensionEnd );
Gizmo.Draw.Line( suspensionStart + Vector3.Forward, suspensionStart + Vector3.Backward );
Gizmo.Draw.Line( suspensionEnd + Vector3.Forward, suspensionEnd + Vector3.Backward );
}
var widthOffset = Vector3.Right * Width * 0.5f;
//
// Wheel radius
//
{
Gizmo.Draw.LineThickness = 0.5f;
Gizmo.Draw.Color = Color.White;
Gizmo.Draw.LineCylinder( widthOffset, -widthOffset, Radius, Radius, 16 );
}
//
// Wheel width
//
{
var circlePosition = Vector3.Zero;
Gizmo.Draw.LineThickness = 0.25f;
Gizmo.Draw.Color = Color.White;
for ( float i = 0; i < 16; i++ )
{
var pos = circlePosition + Vector3.Up.RotateAround( Vector3.Zero, new Angles( i / 16 * 360, 0, 0 ) ) * Radius;
Gizmo.Draw.Line( new Line( pos - widthOffset, pos + widthOffset ) );
var pos2 = circlePosition + Vector3.Up.RotateAround( Vector3.Zero, new Angles( (i + 1) / 16 * 360, 0, 0 ) ) * Radius;
Gizmo.Draw.Line( pos - widthOffset, pos2 + widthOffset );
}
}
////
//// Forward direction
////
//{
// var arrowStart = Vector3.Forward * Radius;
// var arrowEnd = arrowStart + Vector3.Forward * 8f;
// Gizmo.Draw.Color = Color.Red;
// Gizmo.Draw.Arrow( arrowStart, arrowEnd, 4, 1 );
//}
}
}

View File

@@ -0,0 +1,18 @@
using Sandbox;
namespace VeloX;
public partial class VeloXWheel
{
[Property] float BrakePowerMax { get; set; } = 3000;
[Property, Group( "Suspension" )] float SuspensionLength { get; set; } = 10;
[Property, Group( "Suspension" )] float SpringStrength { get; set; } = 800;
[Property, Group( "Suspension" )] float SpringDamper { get; set; } = 3000;
[Property, Group( "Traction" )] float ForwardTractionMax { get; set; } = 2600;
[Property, Group( "Traction" )] float SideTractionMultiplier { get; set; } = 20;
[Property, Group( "Traction" )] float SideTractionMaxAng { get; set; } = 25;
[Property, Group( "Traction" )] float SideTractionMax { get; set; } = 2400;
[Property, Group( "Traction" )] float SideTractionMin { get; set; } = 800;
}

View File

@@ -0,0 +1,240 @@
using Sandbox;
using System;
using System.Runtime.Intrinsics.Arm;
using System.Text.RegularExpressions;
namespace VeloX;
[Group( "VeloX" )]
[Title( "VeloX - Wheel" )]
public partial class VeloXWheel : Component
{
[Property] public float Radius { get; set; } = 15;
[Property] public float Width { get; set; } = 6;
[Sync] public float SideSlip { get; private set; }
[Sync] public float ForwardSlip { get; private set; }
[Sync, Range( 0, 1 )] public float BrakePower { get; set; }
[Sync] public float Torque { get; set; }
[Sync, Range( 0, 1 )] public float Brake { get; set; }
[Property] public bool IsFront { get; protected set; }
[Property] public float SteerMultiplier { get; set; }
public float Spin { get; private set; }
public float RPM { get => angularVelocity * 60f / MathF.Tau; set => angularVelocity = value / (60 / MathF.Tau); }
internal float DistributionFactor { get; set; }
private Vector3 StartPos { get; set; }
private static Rotation CylinderOffset => Rotation.FromRoll( 90 );
public SceneTraceResult Trace { get; private set; }
public bool IsOnGround => Trace.Hit;
private float lastSpringOffset;
private Vector2 tractionCycle;
private float angularVelocity;
private float lastFraction;
private RealTimeUntil expandSoundCD;
private RealTimeUntil contractSoundCD;
protected override void OnAwake()
{
base.OnAwake();
if ( StartPos.IsNearZeroLength )
StartPos = LocalPosition;
}
private static float TractionRamp( float slipAngle, float sideTractionMaxAng, float sideTractionMax, float sideTractionMin )
{
sideTractionMaxAng /= 90; // Convert max slip angle to the 0 - 1 range
var x = (slipAngle - sideTractionMaxAng) / (1 - sideTractionMaxAng);
return slipAngle < sideTractionMaxAng ? sideTractionMax : (sideTractionMax * (1 - x)) + (sideTractionMin * x);
}
private void DoSuspensionSounds( VeloXBase vehicle, float change )
{
if ( change > 0.1f && expandSoundCD )
{
expandSoundCD = 0.3f;
var sound = Sound.Play( vehicle.SuspensionUpSound, WorldPosition );
sound.Volume = Math.Clamp( Math.Abs( change ) * 5f, 0, 0.5f );
}
if ( change < -0.1f && contractSoundCD )
{
contractSoundCD = 0.3f;
change = MathF.Abs( change );
var sound = Sound.Play( change > 0.3f ? vehicle.SuspensionHeavySound : vehicle.SuspensionDownSound, WorldPosition );
sound.Volume = Math.Clamp( change * 5f, 0, 1 );
}
}
internal void Update( VeloXBase vehicle, in float dt )
{
UpdateVisuals( vehicle, dt );
if ( !IsOnGround )
{
angularVelocity += (Torque / 20) * dt;
angularVelocity = MathX.Approach( angularVelocity, 0, dt * 4 );
}
}
private void UpdateVisuals( VeloXBase vehicle, in float dt )
{
//Rotate the wheel around the axle axis
Spin = (Spin - MathX.RadianToDegree( angularVelocity ) * dt) % 360;
WorldRotation = vehicle.WorldTransform.RotationToWorld( vehicle.SteerAngle * SteerMultiplier ).RotateAroundAxis( Vector3.Right, Spin );
}
public void DoPhysics( VeloXBase vehicle, ref Vector3 vehVel, ref Vector3 vehAngVel, ref Vector3 outLin, ref Vector3 outAng, in float dt )
{
var pos = vehicle.WorldTransform.PointToWorld( StartPos );
var ang = vehicle.WorldTransform.RotationToWorld( vehicle.SteerAngle * SteerMultiplier );
var fw = ang.Forward;
var rt = ang.Right;
var up = ang.Up;
var maxLen = SuspensionLength;
var endPos = pos + ang.Down * maxLen;
Trace = Scene.Trace.IgnoreGameObjectHierarchy( vehicle.GameObject )
.FromTo( pos, endPos )
.Cylinder( Width, Radius )
.Rotated( vehicle.WorldTransform.Rotation * CylinderOffset )
.UseRenderMeshes( false )
.UseHitPosition( false )
.WithoutTags( vehicle.WheelIgnoredTags )
.Run();
var fraction = Trace.Fraction;
var contactPos = pos - maxLen * fraction * up;
LocalPosition = vehicle.WorldTransform.PointToLocal( contactPos );
DoSuspensionSounds( vehicle, fraction - lastFraction );
lastFraction = fraction;
if ( !IsOnGround )
{
SideSlip = 0;
ForwardSlip = 0;
return;
}
var normal = Trace.Normal;
var vel = vehicle.Body.GetVelocityAtPoint( pos );
// Split that velocity among our local directions
var velF = fw.Dot( vel );
var velR = rt.Dot( vel );
var velU = normal.Dot( vel );
var absVelR = Math.Abs( velR );
//Make forward forces be perpendicular to the surface normal
fw = normal.Cross( rt );
//Suspension spring force &damping
var offset = maxLen - (fraction * maxLen);
var springForce = (offset * SpringStrength);
var damperForce = (lastSpringOffset - offset) * SpringDamper;
lastSpringOffset = offset;
var force = (springForce - damperForce) * up.Dot( normal ) * normal;
//If the suspension spring is going to be fully compressed on the next frame...
if ( velU < 0 && offset + Math.Abs( velU * dt ) > SuspensionLength )
{
var (linearVel, angularVel) = vehicle.Body.PhysicsBody.CalculateVelocityOffset( (-velU / dt) * normal, pos );
vehVel += linearVel;
vehAngVel += angularVel;
}
//Rolling resistance
force += 0.05f * -velF * fw;
//Brake and torque forces
var surfaceGrip = 1;
var maxTraction = ForwardTractionMax * surfaceGrip * 1;
//Grip loss logic
var brakeForce = MathX.Clamp( -velF, -Brake, Brake ) * BrakePowerMax * surfaceGrip;
var forwardForce = Torque + brakeForce;
var signForwardForce = forwardForce > 0 ? 1 : (forwardForce < 0 ? -1 : 0);
// Given an amount of sideways slippage( up to the max.traction )
// and the forward force, calculate how much grip we are losing.
tractionCycle.x = Math.Min( absVelR, maxTraction );
tractionCycle.y = forwardForce;
var gripLoss = Math.Max( tractionCycle.Length - maxTraction, 0 );
// Reduce the forward force by the amount of grip we lost,
// but still allow some amount of brake force to apply regardless.
forwardForce += -(gripLoss * signForwardForce) + MathX.Clamp( brakeForce * 0.5f, -maxTraction, maxTraction );
force += fw * forwardForce;
// Get how fast the wheel would be spinning if it had never lost grip
var groundAngularVelocity = MathF.Tau * (velF / (Radius * MathF.Tau));
// Add our grip loss to our spin velocity
var _angvel = groundAngularVelocity + gripLoss * (Torque > 0 ? 1 : (Torque < 0 ? -1 : 0));
// Smoothly match our current angular velocity to the angular velocity affected by grip loss
angularVelocity = MathX.Approach( angularVelocity, _angvel, dt * 200 );
ForwardSlip = groundAngularVelocity - angularVelocity;
// Calculate side slip angle
var slipAngle = MathF.Atan2( velR, MathF.Abs( velF ) ) / MathF.PI * 2;
SideSlip = slipAngle * MathX.Clamp( vehicle.TotalSpeed * 0.005f, 0, 1 ) * 2;
//Sideways traction ramp
slipAngle = MathF.Abs( slipAngle * slipAngle );
maxTraction = TractionRamp( slipAngle, SideTractionMaxAng, SideTractionMax, SideTractionMin );
var sideForce = -rt.Dot( vel * SideTractionMultiplier );
// Reduce sideways traction force as the wheel slips forward
sideForce *= 1 - Math.Clamp( MathF.Abs( gripLoss ) * 0.1f, 0, 1 ) * 0.9f;
// Apply sideways traction force
force += Math.Clamp( sideForce, -maxTraction, maxTraction ) * surfaceGrip * rt;
force += velR * SideTractionMultiplier * -0.1f * rt;
//Apply the forces at the axle / ground contact position
vehicle.Body.ApplyForceAt( pos, force / dt );
}
}

358
Code/Car/VeloXCar.Engine.cs Normal file
View File

@@ -0,0 +1,358 @@
using Sandbox;
using System;
using System.Collections.Generic;
namespace VeloX;
public partial class VeloXCar
{
[Property, Feature( "Engine" )] public EngineStream Stream { get; set; }
public EngineStreamPlayer StreamPlayer { get; set; }
[Property, Feature( "Engine" )] public float MinRPM { get; set; } = 800;
[Property, Feature( "Engine" )] public float MaxRPM { get; set; } = 7000;
[Property, Feature( "Engine" ), Range( -1, 1 )]
public float PowerDistribution
{
get => powerDistribution; set
{
powerDistribution = value;
UpdatePowerDistribution();
}
}
[Property, Feature( "Engine" )] public float FlyWheelMass { get; set; } = 80f;
[Property, Feature( "Engine" )] public float FlyWheelRadius { get; set; } = 0.5f;
[Property, Feature( "Engine" )] public float FlywheelFriction { get; set; } = -6000;
[Property, Feature( "Engine" )] public float FlywheelTorque { get; set; } = 20000;
[Property, Feature( "Engine" )] public float EngineBrakeTorque { get; set; } = 2000;
[Property, Feature( "Engine" )]
public Dictionary<int, float> Gears { get; set; } = new()
{
[-1] = 2.5f,
[0] = 0f,
[1] = 2.8f,
[2] = 1.7f,
[3] = 1.2f,
[4] = 0.9f,
[5] = 0.75f,
[6] = 0.7f
};
[Property, Feature( "Engine" )] public float DifferentialRatio { get; set; } = 1f;
[Property, Feature( "Engine" ), Range( 0, 1 )] public float TransmissionEfficiency { get; set; } = 0.8f;
[Property, Feature( "Engine" )] private float MinRPMTorque { get; set; } = 5000f;
[Property, Feature( "Engine" )] private float MaxRPMTorque { get; set; } = 8000f;
[Sync] public int Gear { get; set; } = 0;
[Sync] public float Clutch { get; set; } = 1;
[Sync( SyncFlags.Interpolate )] public float EngineRPM { get; set; }
public float RPMPercent => (EngineRPM - MinRPM) / MaxRPM;
private const float TAU = MathF.Tau;
private int MinGear { get; set; }
private int MaxGear { get; set; }
[Sync] public bool IsRedlining { get; private set; }
private float flywheelVelocity;
private TimeUntil switchCD = 0;
private float groundedCount;
private float burnout;
private float frontBrake;
private float rearBrake;
private float availableFrontTorque;
private float availableRearTorque;
private float avgSideSlip;
private float avgPoweredRPM;
private float avgForwardSlip;
private float inputThrottle, inputBrake;
private bool inputHandbrake;
private float transmissionRPM;
private float powerDistribution;
public float FlywheelRPM
{
get => flywheelVelocity * 60 / TAU;
set
{
flywheelVelocity = value * TAU / 60; EngineRPM = value;
}
}
private void UpdateGearList()
{
int minGear = 0;
int maxGear = 0;
foreach ( var (gear, ratio) in Gears )
{
if ( gear < minGear )
minGear = gear;
if ( gear > maxGear )
maxGear = gear;
if ( minGear != 0 || maxGear != 0 )
{
SwitchGear( 0, false );
}
}
MinGear = minGear;
MaxGear = maxGear;
}
public void SwitchGear( int index, bool cooldown = true )
{
if ( Gear == index ) return;
index = Math.Clamp( index, MinGear, MaxGear );
if ( index == 0 || !cooldown )
switchCD = 0;
else
switchCD = 0.3f;
Clutch = 1;
Gear = index;
}
public float TransmissionToEngineRPM( int gear ) => avgPoweredRPM * Gears[gear] * DifferentialRatio * 60 / TAU;
public float GetTransmissionMaxRPM( int gear ) => FlywheelRPM / Gears[gear] / DifferentialRatio;
private void UpdatePowerDistribution()
{
if ( Wheels is null ) return;
int frontCount = 0, rearCount = 0;
foreach ( var wheel in Wheels )
{
if ( wheel.IsFront )
frontCount++;
else
rearCount++;
}
float frontDistribution = 0.5f + PowerDistribution * 0.5f;
float rearDistribution = 1 - frontDistribution;
frontDistribution /= frontCount;
rearDistribution /= rearCount;
foreach ( var wheel in Wheels )
if ( wheel.IsFront )
wheel.DistributionFactor = frontDistribution;
else
wheel.DistributionFactor = rearDistribution;
}
private void EngineAccelerate( float torque, float dt )
{
var inertia = 0.5f * FlyWheelMass * FlyWheelRadius * FlyWheelRadius;
var angularAcceleration = torque / inertia;
flywheelVelocity += angularAcceleration * dt;
}
private float GetTransmissionTorque( int gear, float minTorque, float maxTorque )
{
var torque = FlywheelRPM.Remap( MinRPM, MaxRPM, minTorque, maxTorque, true );
torque *= (1 - Clutch);
torque = torque * Gears[gear] * DifferentialRatio * TransmissionEfficiency;
return gear == -1 ? -torque : torque;
}
private void AutoGearSwitch()
{
if ( ForwardSpeed < 100 && Input.Down( "Backward" ) )
{
SwitchGear( -1, false );
return;
}
var currentGear = Gear;
if ( currentGear < 0 && ForwardSpeed < -100 )
return;
if ( Math.Abs( avgForwardSlip ) > 10 )
return;
var gear = Math.Clamp( currentGear, 1, MaxGear );
float minRPM = MinRPM, maxRPM = MaxRPM;
maxRPM *= 0.98f;
float gearRPM;
for ( int i = 1; i <= MaxGear; i++ )
{
gearRPM = TransmissionToEngineRPM( i );
if ( (i == 1 && gearRPM < minRPM) || (gearRPM > minRPM && gearRPM < maxRPM) )
{
gear = i;
break;
}
}
var threshold = minRPM + (maxRPM - minRPM) * (0.5 - Throttle * 0.3);
if ( gear < currentGear && gear > currentGear - 2 && EngineRPM > threshold )
return;
SwitchGear( gear );
}
private float EngineClutch( float dt )
{
if ( !switchCD )
{
inputThrottle = 0;
return 0;
}
if ( inputHandbrake )
return 1;
var absForwardSpeed = Math.Abs( ForwardSpeed );
if ( groundedCount < 1 && absForwardSpeed > 30 )
return 1;
if ( ForwardSpeed < -50 && inputBrake > 0 && Gear < 0 )
return 1;
if ( absForwardSpeed > 200 )
return 0;
return inputThrottle > 0.1f ? 0 : 1;
}
private void EngineThink( float dt )
{
inputThrottle = Input.Down( "Forward" ) ? 1 : 0;
inputBrake = Input.Down( "Backward" ) ? 1 : 0;
inputHandbrake = Input.Down( "Jump" );
if ( burnout > 0 )
{
SwitchGear( 1, false );
if ( inputThrottle < 0.1f || inputBrake < 0.1f )
burnout = 0;
}
else
AutoGearSwitch();
if ( Gear < 0 )
(inputBrake, inputThrottle) = (inputThrottle, inputBrake);
var rpm = FlywheelRPM;
var clutch = EngineClutch( dt );
if ( inputThrottle > 0.1 && inputBrake > 0.1 && Math.Abs( ForwardSpeed ) < 50 )
{
burnout = MathX.Approach( burnout, 1, dt * 2 );
Clutch = 0;
}
else if ( inputHandbrake )
{
frontBrake = 0f;
rearBrake = 0.5f;
Clutch = 1;
clutch = 1;
}
else
{
if ( (Gear == -1 || Gear == 1) && inputThrottle < 0.05f && inputBrake < 0.1f && groundedCount > 1 && rpm < MinRPM * 1.2f )
inputBrake = 0.2f;
frontBrake = inputBrake * 0.5f;
rearBrake = inputBrake * 0.5f;
}
clutch = MathX.Approach( Clutch, clutch, dt * ((Gear < 2 && inputThrottle > 0.1f) ? 6 : 2) );
Clutch = clutch;
var isRedlining = false;
transmissionRPM = 0;
if ( Gear != 0 )
{
transmissionRPM = TransmissionToEngineRPM( Gear );
transmissionRPM = Gear < 0 ? -transmissionRPM : transmissionRPM;
rpm = (rpm * clutch) + (MathF.Max( 0, transmissionRPM ) * (1 - clutch));
}
var throttle = Throttle;
var gearTorque = GetTransmissionTorque( Gear, MinRPMTorque, MaxRPMTorque );
var availableTorque = gearTorque * throttle;
if ( transmissionRPM < 0 )
{
availableTorque += gearTorque * 2;
}
else
{
var engineBrakeTorque = GetTransmissionTorque( Gear, EngineBrakeTorque, EngineBrakeTorque );
availableTorque -= engineBrakeTorque * (1 - throttle) * 0.5f;
}
var maxRPM = MaxRPM;
if ( rpm < MinRPM )
{
rpm = MinRPM;
}
else if ( rpm > maxRPM )
{
if ( rpm > maxRPM * 1.2f )
availableTorque = 0;
rpm = maxRPM;
if ( Gear != MaxGear || groundedCount < Wheels.Count )
isRedlining = true;
}
FlywheelRPM = Math.Clamp( rpm, 0, maxRPM );
if ( burnout > 0 )
availableTorque += availableTorque * burnout * 0.1f;
var front = 0.5f + PowerDistribution * 0.5f;
var rear = 1 - front;
availableFrontTorque = availableTorque * front;
availableRearTorque = availableTorque * rear;
throttle = MathX.Approach( throttle, inputThrottle, dt * 4 );
EngineAccelerate( FlywheelFriction + FlywheelTorque * throttle, dt );
Throttle = throttle;
IsRedlining = (isRedlining && inputThrottle > 0);
}
public void StreamEngineUpdate()
{
}
}

View File

@@ -0,0 +1,46 @@
using Sandbox;
using System;
using System.Threading;
namespace VeloX;
public partial class VeloXCar
{
public static float ExpDecay( float a, float b, float decay, float dt ) => b + (a - b) * MathF.Exp( -decay * dt );
[Property, Feature( "Steer" )] public float SteerConeMaxSpeed { get; set; } = 1800;
[Property, Feature( "Steer" )] public float SteerConeMaxAngle { get; set; } = 0.25f;
[Property, Feature( "Steer" )] public float SteerConeChangeRate { get; set; } = 8;
[Property, Feature( "Steer" )] public float CounterSteer { get; set; } = 0.1f;
[Property, Feature( "Steer" )] public float MaxSteerAngle { get; set; } = 35f;
[Sync] public float Steering { get; private set; }
private float jTurnMultiplier;
private float inputSteer;
private void UpdateSteering( float dt )
{
var inputSteer = Input.AnalogMove.y;
var absInputSteer = Math.Abs( inputSteer );
var sideSlip = Math.Clamp( avgSideSlip, -1, 1 );
var steerConeFactor = Math.Clamp( TotalSpeed / SteerConeMaxSpeed, 0, 1 );
var steerCone = 1 - steerConeFactor * (1 - SteerConeMaxAngle);
steerCone = Math.Clamp( steerCone, Math.Abs( sideSlip ), 1 );
inputSteer = ExpDecay( this.inputSteer, inputSteer * steerCone, SteerConeChangeRate, dt );
this.inputSteer = inputSteer;
var counterSteer = sideSlip * steerConeFactor * (1 - absInputSteer);
counterSteer = Math.Clamp( counterSteer, -1, 1 ) * CounterSteer;
inputSteer = Math.Clamp( inputSteer + counterSteer, -1, 1 );
Steering = inputSteer;
SteerAngle = new( 0, inputSteer * MaxSteerAngle, 0 );
if ( ForwardSpeed < -100 )
jTurnMultiplier = 0.5f;
else
jTurnMultiplier = ExpDecay( jTurnMultiplier, 1, 2, dt );
}
}

View File

@@ -0,0 +1,46 @@
namespace VeloX;
public partial class VeloXCar
{
private void WheelThink( in float dt )
{
var maxRPM = GetTransmissionMaxRPM( Gear );
var frontTorque = availableFrontTorque;
var rearTorque = availableRearTorque;
groundedCount = 0;
float avgRPM = 0, totalSideSlip = 0, totalForwardSlip = 0;
foreach ( var w in Wheels )
{
w.Update( this, dt );
totalSideSlip += w.SideSlip;
totalForwardSlip += w.ForwardSlip;
var rpm = w.RPM;
avgRPM += rpm * w.DistributionFactor;
w.Torque = w.DistributionFactor * (w.IsFront ? frontTorque : rearTorque);
w.Brake = w.IsFront ? frontBrake : rearBrake;
if ( inputHandbrake && !w.IsFront )
w.RPM = 0;
if ( rpm > maxRPM )
w.RPM = maxRPM;
if ( w.IsOnGround )
groundedCount++;
}
avgPoweredRPM = avgRPM;
avgSideSlip = totalSideSlip / Wheels.Count;
avgForwardSlip = totalForwardSlip / Wheels.Count;
}
}

60
Code/Car/VeloXCar.cs Normal file
View File

@@ -0,0 +1,60 @@
using Sandbox;
using System;
namespace VeloX;
[Group( "VeloX" )]
[Title( "VeloX - Car" )]
public partial class VeloXCar : VeloXBase
{
protected override void OnAwake()
{
base.OnAwake();
StreamPlayer = new( Stream );
}
protected override void OnStart()
{
base.OnStart();
if ( !IsProxy )
{
UpdateGearList();
UpdatePowerDistribution();
}
}
protected override void OnUpdate()
{
base.OnUpdate();
if ( StreamPlayer is not null )
{
StreamPlayer.Throttle = Throttle;
StreamPlayer.RPMPercent = RPMPercent;
StreamPlayer.EngineState = EngineState;
StreamPlayer.IsRedlining = IsRedlining;
if ( Driver.IsValid() && Driver.IsProxy )
StreamPlayer.Update( Time.Delta, Scene.Camera.WorldPosition );
else
StreamPlayer.Update( Time.Delta, WorldPosition );
}
}
protected override void OnFixedUpdate()
{
if ( IsProxy )
return;
base.OnFixedUpdate();
var dt = Time.Delta;
EngineThink( dt );
WheelThink( dt );
UpdateSteering( dt );
Brake = Math.Clamp( frontBrake + rearBrake + (Input.Down( "Jump" ) ? 1 : 0), 0, 1 );
}
}

9
Code/Enum/EngineState.cs Normal file
View File

@@ -0,0 +1,9 @@
namespace VeloX;
public enum EngineState
{
Off,
Starting,
Running,
ShuttingDown,
}

9
Code/Enum/WaterState.cs Normal file
View File

@@ -0,0 +1,9 @@
namespace VeloX;
public enum WaterState
{
NotOnWater, // 0: Не на воде
PartialContact, // 1: Хотя бы одна точка плавучести на воде
HalfSubmerged, // 2: Хотя бы половина точек плавучести на воде
FullySubmerged // 3: Полностью погружён
}

View File

@@ -0,0 +1,47 @@
using Sandbox;
namespace VeloX;
public class InputResolver
{
public GameObject Driver { get; internal set; }
private bool IsDriverActive => Driver.IsValid();
public Vector2 MouseDelta => IsDriverActive ? Input.MouseDelta : default;
public Vector2 MouseWheel => IsDriverActive ? Input.MouseWheel : default;
public Angles AnalogLook => IsDriverActive ? Input.AnalogLook : default;
public Vector3 AnalogMove => IsDriverActive ? Input.AnalogMove : default;
public bool Down( string action )
{
return IsDriverActive && Input.Down( action );
}
public bool Pressed( string action )
{
return IsDriverActive && Input.Pressed( action );
}
public bool Released( string action )
{
return IsDriverActive && Input.Released( action );
}
public void TriggerHaptics( float leftMotor, float rightMotor, float leftTrigger = 0f, float rightTrigger = 0f, int duration = 500 )
{
if ( IsDriverActive )
{
Input.TriggerHaptics( leftMotor, rightMotor, leftTrigger, rightTrigger, duration );
}
}
public void StopAllHaptics()
{
if ( IsDriverActive )
{
Input.StopAllHaptics();
}
}
}

View File

@@ -0,0 +1,87 @@
using Sandbox;
using System;
using System.Text.Json;
using System.Text.Json.Serialization;
namespace VeloX.Audio;
[JsonConverter( typeof( ControllerConverter ) )]
public sealed class Controller
{
public enum InputTypes
{
Throttle,
RpmFraction,
}
public enum OutputTypes
{
Volume,
Pitch,
}
public required InputTypes InputParameter { get; set; }
[Property] public ValueRange InputRange { get; set; }
public required OutputTypes OutputParameter { get; set; }
public ValueRange OutputRange { get; set; }
}
public record struct ValueRange
{
public ValueRange( float inputMin, float inputMax )
{
Min = inputMin;
Max = inputMax;
}
[Range( 0, 1 )] public float Min { get; set; }
[Range( 0, 1 )] public float Max { get; set; }
public readonly float Remap( float value, float newMin, float newMax )
{
var normalized = (value - Min) / (Max - Min);
return newMin + normalized * (newMax - newMin);
}
};
public sealed class ControllerConverter : JsonConverter<Controller>
{
public override Controller Read( ref Utf8JsonReader reader, Type typeToConvert, JsonSerializerOptions options )
{
if ( reader.TokenType != JsonTokenType.StartArray )
throw new JsonException( "Expected array for Controller" );
reader.Read();
string inputParam = reader.GetString() ?? string.Empty;
reader.Read();
float inputMin = reader.GetSingle();
reader.Read();
float inputMax = reader.GetSingle();
reader.Read();
string outputParam = reader.GetString() ?? string.Empty;
reader.Read();
float outputMin = reader.GetSingle();
reader.Read();
float outputMax = reader.GetSingle();
reader.Read(); // End of array
return new Controller
{
InputParameter = Enum.Parse<Controller.InputTypes>( inputParam, true ),
InputRange = new ValueRange( inputMin, inputMax ),
OutputParameter = Enum.Parse<Controller.OutputTypes>( outputParam, true ),
OutputRange = new ValueRange( outputMin, outputMax )
};
}
public override void Write( Utf8JsonWriter writer, Controller value, JsonSerializerOptions options )
{
writer.WriteStartArray();
writer.WriteStringValue( value.InputParameter.ToString() );
writer.WriteNumberValue( value.InputRange.Min );
writer.WriteNumberValue( value.InputRange.Max );
writer.WriteStringValue( value.OutputParameter.ToString() );
writer.WriteNumberValue( value.OutputRange.Min );
writer.WriteNumberValue( value.OutputRange.Max );
writer.WriteEndArray();
}
}

View File

@@ -0,0 +1,35 @@
using Sandbox;
using System.Collections.Generic;
using VeloX.Audio;
namespace VeloX;
[GameResource( "Engine Stream", "engstr", "Engine Sound", Category = "VeloX", Icon = "time_to_leave" )]
public sealed class EngineStream : GameResource
{
public sealed class Layer
{
[Property,
Title( "Sound File" ),
Description( "Sound asset for this layer" )]
public SoundFile AudioPath { get; set; }
[Property, Title( "Use Redline Effect" ),
Description( "Enable RPM-based vibration effect" )]
public bool UseRedline { get; set; } = true;
[Property, Title( "Controllers" ),
Description( "Audio parameter controllers" )]
public List<Controller> Controllers { get; set; }
[Property, Title( "Is Muted" )]
public bool IsMuted { get; set; }
}
[Property, Title( "Stream Parameters" ),
Description( "Global engine sound parameters" )]
public StreamParameters Parameters { get; set; }
[Property, Title( "Sound Layers" ),
Description( "Individual sound layers" )]
public Dictionary<string, Layer> Layers { get; set; }
}

View File

@@ -0,0 +1,119 @@
using Sandbox;
using Sandbox.Audio;
using System;
using System.Collections.Generic;
using System.IO;
using VeloX.Audio;
using static VeloX.EngineStream;
namespace VeloX;
public class EngineStreamPlayer( EngineStream stream ) : IDisposable
{
private static readonly Mixer EngineMixer = Mixer.FindMixerByName( "Car Engine" );
public EngineStream Stream { get; set; } = stream;
public EngineState EngineState { get; set; }
public bool EngineSoundPaused => EngineState != EngineState.Running;
public float Throttle { get; set; }
public bool IsRedlining { get; set; }
public float RPMPercent { get; set; }
private float _wobbleTime;
public readonly Dictionary<Layer, SoundHandle> EngineSounds = [];
public void Update( float deltaTime, Vector3 position, bool isLocal = false )
{
var globalPitch = 1.0f;
// Gear wobble effect
if ( _wobbleTime > 0 )
{
_wobbleTime -= deltaTime * (0.1f + Throttle);
globalPitch += MathF.Cos( _wobbleTime * Stream.Parameters.WobbleFrequency ) * _wobbleTime * (1 - _wobbleTime) * Stream.Parameters.WobbleStrength;
}
globalPitch *= Stream.Parameters.Pitch;
// Redline effect
var redlineVolume = 1.0f;
if ( IsRedlining )
{
redlineVolume = 1 - Stream.Parameters.RedlineStrength +
MathF.Cos( RealTime.Now * Stream.Parameters.RedlineFrequency ) *
Stream.Parameters.RedlineStrength;
}
// Process layers
foreach ( var (id, layer) in Stream.Layers )
{
EngineSounds.TryGetValue( layer, out var channel );
if ( !channel.IsValid() )
{
channel = Sound.PlayFile( layer.AudioPath );
EngineSounds[layer] = channel;
}
if ( channel.Paused && (EngineSoundPaused || layer.IsMuted) )
continue;
// Reset controller outputs
float layerVolume = 1.0f;
float layerPitch = 1.0f;
// Apply all controllers
foreach ( var controller in layer.Controllers )
{
var inputValue = controller.InputParameter switch
{
Controller.InputTypes.Throttle => Throttle,
Controller.InputTypes.RpmFraction => RPMPercent,
_ => 0.0f
};
var normalized = Math.Clamp( inputValue, controller.InputRange.Min, controller.InputRange.Max );
var outputValue = controller.InputRange.Remap(
normalized,
controller.OutputRange.Min,
controller.OutputRange.Max
);
// Apply to correct parameter
switch ( controller.OutputParameter )
{
case Controller.OutputTypes.Volume:
layerVolume *= outputValue;
break;
case Controller.OutputTypes.Pitch:
layerPitch *= outputValue;
break;
}
}
// Apply redline effect if needed
layerVolume *= layer.UseRedline ? redlineVolume : 1.0f;
layerPitch *= globalPitch;
// Update audio channel
channel.Pitch = layerPitch;
channel.Volume = layerVolume * Stream.Parameters.Volume;
channel.Position = position;
channel.ListenLocal = isLocal;
channel.Paused = EngineSoundPaused || layer.IsMuted;
channel.TargetMixer = EngineMixer;
}
}
public void Dispose()
{
foreach ( var item in EngineSounds )
{
item.Value?.Stop();
item.Value?.Dispose();
}
}
}

View File

@@ -0,0 +1,24 @@
using Sandbox;
namespace VeloX;
public sealed class StreamParameters
{
[Property, Range( 0.1f, 2.0f ), Description( "Base pitch multiplier" )]
public float Pitch { get; set; } = 1.0f;
[Property, Range( 0.0f, 2.0f ), Description( "Base volume level" )]
public float Volume { get; set; } = 1.0f;
[Property, Range( 1f, 100f ), Description( "Vibration frequency at max RPM" )]
public float RedlineFrequency { get; set; } = 55.0f;
[Property, Range( 0.0f, 1.0f ), Description( "Vibration intensity at max RPM" )]
public float RedlineStrength { get; set; } = 0.2f;
[Property, Range( 1f, 50f ), Description( "Idle vibration frequency" )]
public float WobbleFrequency { get; set; } = 25.0f;
[Property, Range( 0.0f, 0.5f ), Description( "Idle vibration intensity" )]
public float WobbleStrength { get; set; } = 0.13f;
}

View File

@@ -0,0 +1,78 @@
using Sandbox;
namespace VeloX;
public static class PhysicsExtensions
{
/// <summary>
/// Calculates the linear and angular velocities on the center of mass for an offset impulse.
/// </summary>
/// <param name="physObj">The physics object</param>
/// <param name="impulse">The impulse acting on the object in kg*units/s (World frame)</param>
/// <param name="position">The location of the impulse in world coordinates</param>
/// <returns>
/// Vector1: Linear velocity from the impulse (World frame)
/// Vector2: Angular velocity from the impulse (Local frame)
/// </returns>
public static (Vector3 LinearVelocity, Vector3 AngularVelocity) CalculateVelocityOffset( this PhysicsBody physObj, Vector3 impulse, Vector3 position )
{
if ( !physObj.IsValid() || !physObj.MotionEnabled )
return (Vector3.Zero, Vector3.Zero);
Vector3 linearVelocity = impulse / physObj.Mass;
Vector3 centerOfMass = physObj.MassCenter;
Vector3 relativePosition = position - centerOfMass;
Vector3 torque = relativePosition.Cross( impulse );
Rotation bodyRotation = physObj.Transform.Rotation;
Vector3 localTorque = bodyRotation.Inverse * torque;
Vector3 localInverseInertia = physObj.Inertia.Inverse;
Vector3 localAngularVelocity = new(
localTorque.x * localInverseInertia.x,
localTorque.y * localInverseInertia.y,
localTorque.z * localInverseInertia.z );
return (linearVelocity, localAngularVelocity);
}
/// <summary>
/// Calculates the linear and angular impulses on the object's center of mass for an offset impulse.
/// </summary>
/// <param name="physObj">The physics object</param>
/// <param name="impulse">The impulse acting on the object in kg*units/s (World frame)</param>
/// <param name="position">The location of the impulse in world coordinates</param>
/// <returns>
/// Vector1: Linear impulse on center of mass (World frame)
/// Vector2: Angular impulse on center of mass (Local frame)
/// </returns>
public static (Vector3 LinearImpulse, Vector3 AngularImpulse) CalculateForceOffset(
this PhysicsBody physObj,
Vector3 impulse,
Vector3 position )
{
if ( !physObj.IsValid() || !physObj.MotionEnabled )
{
return (Vector3.Zero, Vector3.Zero);
}
// 1. Linear impulse is the same as the input impulse (conservation of momentum)
Vector3 linearImpulse = impulse;
// 2. Calculate angular impulse (torque) from the offset force
// τ = r × F (cross product of position relative to COM and force)
Vector3 centerOfMass = physObj.MassCenter;
Vector3 relativePosition = position - centerOfMass;
Vector3 worldAngularImpulse = relativePosition.Cross( impulse );
// Convert angular impulse to local space (since we'll use it with LocalInertia)
Rotation bodyRotation = physObj.Transform.Rotation;
Vector3 localAngularImpulse = bodyRotation.Inverse * worldAngularImpulse;
return (linearImpulse, localAngularImpulse);
}
}

4
Code/velox.csproj.user Normal file
View File

@@ -0,0 +1,4 @@
<?xml version="1.0" encoding="utf-8"?>
<Project ToolsVersion="Current" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<PropertyGroup />
</Project>