From 0ff82f3eac1e2b14cab80c15f5d1e78f3bb50050 Mon Sep 17 00:00:00 2001 From: Valera <108022376+kekobka@users.noreply.github.com> Date: Thu, 12 Jun 2025 22:56:47 +0700 Subject: [PATCH] =?UTF-8?q?=D0=9F=D0=B5=D1=80=D0=B5=D0=BF=D0=B8=D1=81?= =?UTF-8?q?=D0=B0=D0=BB=20=D1=82=D1=80=D0=B5=D0=BD=D0=B8=D0=B5=20=D0=BD?= =?UTF-8?q?=D0=B0=20=D0=BF=D0=B0=D1=81=D0=B5=D0=B9=D0=BA=D1=83=20(=D0=B3?= =?UTF-8?q?=D0=BE=D0=B2=D0=BD=D0=BE)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Code/Base/VeloXBase.Input.cs | 18 +- Code/Base/VeloXBase.Phys.cs | 14 +- Code/Base/VeloXBase.cs | 3 +- Code/Base/Wheel/Friction.cs | 11 + Code/Base/Wheel/FrictionPreset.cs | 16 ++ Code/Base/Wheel/VeloXWheel.Suspension.cs | 18 -- Code/Base/Wheel/VeloXWheel.cs | 344 +++++++++++++++-------- Code/Base/Wheel/WheelFriction.cs | 12 + Code/Car/VeloXCar.Engine.cs | 6 +- Code/Car/VeloXCar.cs | 20 +- 10 files changed, 292 insertions(+), 170 deletions(-) create mode 100644 Code/Base/Wheel/Friction.cs create mode 100644 Code/Base/Wheel/FrictionPreset.cs delete mode 100644 Code/Base/Wheel/VeloXWheel.Suspension.cs create mode 100644 Code/Base/Wheel/WheelFriction.cs diff --git a/Code/Base/VeloXBase.Input.cs b/Code/Base/VeloXBase.Input.cs index ec6fee8..faa966b 100644 --- a/Code/Base/VeloXBase.Input.cs +++ b/Code/Base/VeloXBase.Input.cs @@ -1,11 +1,23 @@ using Sandbox; - +using System; 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; } + + private Guid _guid; + + [Sync( SyncFlags.FromHost )] + public Guid ConnectionID + { + get => _guid; + set + { + _guid = value; + Input.Driver = Connection.Find( _guid ); + } + } + [Property, Feature( "Input" )] public bool IsDriver => ConnectionID == Connection.Local.Id; } diff --git a/Code/Base/VeloXBase.Phys.cs b/Code/Base/VeloXBase.Phys.cs index 35e9f2e..b89cff8 100644 --- a/Code/Base/VeloXBase.Phys.cs +++ b/Code/Base/VeloXBase.Phys.cs @@ -5,7 +5,6 @@ namespace VeloX; public abstract partial class VeloXBase { - private Vector3 linForce; private Vector3 angForce; private void PhysicsSimulate() @@ -14,10 +13,6 @@ public abstract partial class VeloXBase 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; @@ -25,19 +20,12 @@ public abstract partial class VeloXBase 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; + v.DoPhysics( this, in dt ); } - - Body.ApplyForce( linForce ); Body.ApplyTorque( angForce ); } } diff --git a/Code/Base/VeloXBase.cs b/Code/Base/VeloXBase.cs index fb29afe..b408534 100644 --- a/Code/Base/VeloXBase.cs +++ b/Code/Base/VeloXBase.cs @@ -5,7 +5,6 @@ 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; } @@ -24,7 +23,7 @@ public abstract partial class VeloXBase : Component protected override void OnFixedUpdate() { - if ( IsProxy ) + if ( !IsDriver ) return; LocalVelocity = WorldTransform.PointToLocal( WorldPosition + Body.Velocity ); diff --git a/Code/Base/Wheel/Friction.cs b/Code/Base/Wheel/Friction.cs new file mode 100644 index 0000000..997978f --- /dev/null +++ b/Code/Base/Wheel/Friction.cs @@ -0,0 +1,11 @@ +namespace VeloX; + +public struct Friction +{ + public float SlipCoef { get; set; } + public float ForceCoef { get; set; } + + public float Force { get; set; } + public float Slip { get; set; } + public float Speed { get; set; } +} diff --git a/Code/Base/Wheel/FrictionPreset.cs b/Code/Base/Wheel/FrictionPreset.cs new file mode 100644 index 0000000..55909b3 --- /dev/null +++ b/Code/Base/Wheel/FrictionPreset.cs @@ -0,0 +1,16 @@ +using System; + +namespace VeloX; +public class FrictionPreset +{ + public float B { get; set; } = 10.86f; + public float C { get; set; } = 2.15f; + public float D { get; set; } = 0.933f; + public float E { get; set; } = 0.992f; + public float Evaluate( float slip ) + { + var t = Math.Abs( slip ); + + return D * MathF.Sin( C * MathF.Atan( B * t - E * (B * t - MathF.Atan( B * t )) ) ); + } +} diff --git a/Code/Base/Wheel/VeloXWheel.Suspension.cs b/Code/Base/Wheel/VeloXWheel.Suspension.cs deleted file mode 100644 index e3476bc..0000000 --- a/Code/Base/Wheel/VeloXWheel.Suspension.cs +++ /dev/null @@ -1,18 +0,0 @@ -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; - -} diff --git a/Code/Base/Wheel/VeloXWheel.cs b/Code/Base/Wheel/VeloXWheel.cs index 9b97bda..24850c2 100644 --- a/Code/Base/Wheel/VeloXWheel.cs +++ b/Code/Base/Wheel/VeloXWheel.cs @@ -1,7 +1,11 @@ using Sandbox; +using Sandbox.UI; using System; +using System.Buffers.Text; +using System.Numerics; using System.Runtime.Intrinsics.Arm; using System.Text.RegularExpressions; +using System.Threading; namespace VeloX; @@ -11,14 +15,34 @@ public partial class VeloXWheel : Component { [Property] public float Radius { get; set; } = 15; + [Property] public float Mass { get; set; } = 20; + [Property] public float RollingResistance { get; set; } = 20; + [Property] public float SlipCircleShape { get; set; } = 1.05f; + + public FrictionPreset LongitudinalFrictionPreset => WheelFriction.Longitudinal; + public FrictionPreset LateralFrictionPreset => WheelFriction.Lateral; + public FrictionPreset AligningFrictionPreset => WheelFriction.Aligning; + + [Property] public WheelFriction WheelFriction { get; set; } + + [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] float BrakePowerMax { get; set; } = 3000; [Property] public bool IsFront { get; protected set; } [Property] public float SteerMultiplier { get; set; } + [Property] public float CasterAngle { get; set; } = 7; // todo + [Property] public float CamberAngle { get; set; } = -3; + [Property] public float ToeAngle { get; set; } = 0.5f; + + [Property, Group( "Suspension" )] float SuspensionLength { get; set; } = 10; + [Property, Group( "Suspension" )] float SpringStrength { get; set; } = 800; + [Property, Group( "Suspension" )] float SpringDamper { get; set; } = 3000; + public float Spin { get; private set; } public float RPM { get => angularVelocity * 60f / MathF.Tau; set => angularVelocity = value / (60 / MathF.Tau); } @@ -31,12 +55,23 @@ public partial class VeloXWheel : Component public bool IsOnGround => Trace.Hit; private float lastSpringOffset; - private Vector2 tractionCycle; private float angularVelocity; + private float load; private float lastFraction; private RealTimeUntil expandSoundCD; private RealTimeUntil contractSoundCD; + private Vector3 contactPos; + private Vector3 forward; + private Vector3 right; + private Vector3 up; + + private Friction forwardFriction; + private Friction sideFriction; + private Vector3 force; + + private float BaseInertia => 0.5f * Mass * MathF.Pow( Radius.InchToMeter(), 2 ); + private float Inertia => BaseInertia; protected override void OnAwake() { @@ -45,15 +80,6 @@ public partial class VeloXWheel : Component 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 ) @@ -75,41 +101,145 @@ public partial class VeloXWheel : Component 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; + var entityAngles = vehicle.WorldRotation; - WorldRotation = vehicle.WorldTransform.RotationToWorld( vehicle.SteerAngle * SteerMultiplier ).RotateAroundAxis( Vector3.Right, Spin ); + Spin -= angularVelocity.MeterToInch() * dt; + + + var steerRotated = entityAngles.RotateAroundAxis( Vector3.Up, vehicle.SteerAngle.yaw * SteerMultiplier + ToeAngle ); + var camberRotated = steerRotated.RotateAroundAxis( Vector3.Forward, -CamberAngle ); + var angularVelocityRotated = camberRotated.RotateAroundAxis( Vector3.Right, Spin ); + + WorldRotation = angularVelocityRotated; } - public void DoPhysics( VeloXBase vehicle, ref Vector3 vehVel, ref Vector3 vehAngVel, ref Vector3 outLin, ref Vector3 outAng, in float dt ) + private (float, float, float, float) StepLongitudinal( float Vx, float Lc, float kFx, float kSx, float dt ) { + float Tm = Torque; + float Tb = Brake * BrakePowerMax + RollingResistance; + float R = Radius.InchToMeter(); + float I = Inertia; + float Winit = angularVelocity; + float W = angularVelocity; + + float VxAbs = MathF.Abs( Vx ); + float Sx; + if ( VxAbs >= 0.1f ) + Sx = (Vx - W * R) / VxAbs; + + else + Sx = (Vx - W * R) * 0.6f; + + Sx = Math.Clamp( Sx * kSx, -1, 1 ); + + W += Tm / I * dt; + + Tb *= W > 0 ? -1 : 1; + + float TbCap = MathF.Abs( W ) * I / dt; + float Tbr = MathF.Abs( Tb ) - MathF.Abs( TbCap ); + Tbr = MathF.Max( Tbr, 0 ); + Tb = Math.Clamp( Tb, -TbCap, TbCap ); + W += Tb / I * dt; + + float maxTorque = LongitudinalFrictionPreset.Evaluate( Sx ) * Lc * kFx; + + float errorTorque = (W - Vx / R) * I / dt; + + float surfaceTorque = MathX.Clamp( errorTorque, -maxTorque, maxTorque ); + + W -= surfaceTorque / I * dt; + + float Fx = surfaceTorque / R; + + + Tbr *= W > 0 ? -1 : 1; + float TbCap2 = MathF.Abs( W ) * I / dt; + + float Tb2 = Math.Clamp( Tbr, -TbCap2, TbCap2 ); + + W += Tb2 / I * dt; + + float deltaOmegaTorque = (W - Winit) * I / dt; + + float Tcnt = -surfaceTorque + Tb + Tb2 - deltaOmegaTorque; + if ( Lc < 0.001f ) + Sx = 0; + + return (W, Sx, Fx, Tcnt); + } + + private (float, float) StepLateral( float Vx, float Vy, float Lc, float kFy, float kSy, float dt ) + { + float VxAbs = MathF.Abs( Vx ); + float Sy; + + if ( VxAbs > 0.1f ) + Sy = MathF.Atan( Vy / VxAbs ).RadianToDegree() * 0.01111f; + else + Sy = Vy * (0.003f / dt); + + + Sy *= kSy * 0.95f; + Sy = Math.Clamp( Sy * kSy, -1, 1 ); + float Fy = -MathF.Sign( Sy ) * LateralFrictionPreset.Evaluate( Sy ) * Lc * kFy; + if ( Lc < 0.0001f ) + Sy = 0; + + return (Sy, Fy); + } + + private void SlipCircle( float Sx, float Sy, float Fx, ref float Fy ) + { + float SxAbs = Math.Abs( Sx ); + if ( SxAbs > 0.01f ) + { + + float SxClamped = Math.Clamp( Sx, -1, 1 ); + + float SyClamped = Math.Clamp( Sy, -1, 1 ); + + Vector2 combinedSlip = new( + SxClamped * SlipCircleShape, + SyClamped + ); + + Vector2 slipDir = combinedSlip.Normal; + + float F = MathF.Sqrt( Fx * Fx + Fy * Fy ); + + float absSlipDirY = MathF.Abs( slipDir.y ); + + Fy = F * absSlipDirY * MathF.Sign( Fy ); + } + } + + + private static float GetLongitudinalLoadCoefficient( float load ) => 11000 * (1 - MathF.Exp( -0.00014f * load )); + private static float GetLateralLoadCoefficient( float load ) => 18000 * (1 - MathF.Exp( -0.0001f * load )); + + public void DoPhysics( VeloXBase vehicle, 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; + forward = ang.Forward; + right = ang.Right; + up = ang.Up; var maxLen = SuspensionLength; var endPos = pos + ang.Down * maxLen; - Trace = Scene.Trace.IgnoreGameObjectHierarchy( vehicle.GameObject ) - .FromTo( pos, endPos ) - .Cylinder( Width, Radius ) + Trace = Scene.Trace + .IgnoreGameObjectHierarchy( vehicle.GameObject ) + .Cylinder( Width, Radius, pos, endPos ) .Rotated( vehicle.WorldTransform.Rotation * CylinderOffset ) .UseRenderMeshes( false ) .UseHitPosition( false ) @@ -118,123 +248,107 @@ public partial class VeloXWheel : Component var fraction = Trace.Fraction; - var contactPos = pos - maxLen * fraction * up; + contactPos = pos - maxLen * fraction * up; LocalPosition = vehicle.WorldTransform.PointToLocal( contactPos ); DoSuspensionSounds( vehicle, fraction - lastFraction ); lastFraction = fraction; + var normal = Trace.Normal; + + var vel = vehicle.Body.GetVelocityAtPoint( pos ); + + vel.x = vel.x.InchToMeter(); + vel.y = vel.y.InchToMeter(); + vel.z = vel.z.InchToMeter(); + 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; + force = (springForce - damperForce) * MathF.Max( 0, up.Dot( normal ) ) * normal / dt; - //If the suspension spring is going to be fully compressed on the next frame... + // Vector3.CalculateVelocityOffset is broken (need fix) + //var velU = normal.Dot( vel ).MeterToInch(); + //if ( velU < 0 && offset + Math.Abs( velU * dt ) > SuspensionLength ) + //{ + // var (linearVel, angularVel) = vehicle.Body.PhysicsBody.CalculateVelocityOffset( (-velU.InchToMeter() / dt) * normal, pos ); + // vehicle.Body.Velocity += linearVel; + // vehicle.Body.AngularVelocity += angularVel; + //} - if ( velU < 0 && offset + Math.Abs( velU * dt ) > SuspensionLength ) + + load = springForce - damperForce; + load = Math.Max( load, 0 ); + + var longitudinalLoadCoefficient = GetLongitudinalLoadCoefficient( load ); + var lateralLoadCoefficient = GetLateralLoadCoefficient( load ); + + float forwardSpeed = 0; + float sideSpeed = 0; + + + if ( IsOnGround ) { - var (linearVel, angularVel) = vehicle.Body.PhysicsBody.CalculateVelocityOffset( (-velU / dt) * normal, pos ); - vehVel += linearVel; - vehAngVel += angularVel; + forwardSpeed = vel.Dot( forward ); + sideSpeed = vel.Dot( right ); } - //Rolling resistance - force += 0.05f * -velF * fw; + (float W, float Sx, float Fx, float _) = StepLongitudinal( + forwardSpeed, + longitudinalLoadCoefficient, + 0.95f, + 0.9f, + dt + ); - //Brake and torque forces - var surfaceGrip = 1; + (float Sy, float Fy) = StepLateral( + forwardSpeed, + sideSpeed, + lateralLoadCoefficient, + 0.95f, + 0.9f, + dt + ); - var maxTraction = ForwardTractionMax * surfaceGrip * 1; - //Grip loss logic + SlipCircle( Sx, Sy, Fx, ref Fy ); + angularVelocity = W; - var brakeForce = MathX.Clamp( -velF, -Brake, Brake ) * BrakePowerMax * surfaceGrip; + forwardFriction = new Friction() + { + Slip = Sx, + Force = Fx.MeterToInch(), + Speed = forwardSpeed + }; - 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 ); + sideFriction = new Friction() + { + Slip = Sy, + Force = Fy.MeterToInch(), + Speed = sideSpeed + }; - // 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 ); + var frictionforce = right * sideFriction.Force + forward * forwardFriction.Force; + vehicle.Body.ApplyForceAt( contactPos, force + frictionforce ); } + + + // debug + protected override void OnUpdate() + { + DebugOverlay.Normal( contactPos, forward * forwardFriction.Force / 10000f, Color.Red, overlay: true ); + DebugOverlay.Normal( contactPos, right * sideFriction.Force / 10000f, Color.Green, overlay: true ); + DebugOverlay.Normal( contactPos, up * force / 50000f, Color.Blue, overlay: true ); + } } diff --git a/Code/Base/Wheel/WheelFriction.cs b/Code/Base/Wheel/WheelFriction.cs new file mode 100644 index 0000000..d2925b9 --- /dev/null +++ b/Code/Base/Wheel/WheelFriction.cs @@ -0,0 +1,12 @@ +using Sandbox; + +namespace VeloX; + + +[GameResource( "Wheel Friction", "whfric", "Wheel Friction", Category = "VeloX", Icon = "radio_button_checked" )] +public class WheelFriction : GameResource +{ + public FrictionPreset Longitudinal { get; set; } + public FrictionPreset Lateral { get; set; } + public FrictionPreset Aligning { get; set; } +} diff --git a/Code/Car/VeloXCar.Engine.cs b/Code/Car/VeloXCar.Engine.cs index 702fab5..c6e47ee 100644 --- a/Code/Car/VeloXCar.Engine.cs +++ b/Code/Car/VeloXCar.Engine.cs @@ -6,6 +6,7 @@ namespace VeloX; public partial class VeloXCar { + [Property, Feature( "Engine" ), Sync] public EngineState EngineState { get; set; } [Property, Feature( "Engine" )] public EngineStream Stream { get; set; } public EngineStreamPlayer StreamPlayer { get; set; } @@ -181,7 +182,6 @@ public partial class VeloXCar if ( currentGear < 0 && ForwardSpeed < -100 ) return; - if ( Math.Abs( avgForwardSlip ) > 10 ) return; @@ -351,8 +351,4 @@ public partial class VeloXCar IsRedlining = (isRedlining && inputThrottle > 0); } - public void StreamEngineUpdate() - { - - } } diff --git a/Code/Car/VeloXCar.cs b/Code/Car/VeloXCar.cs index 2619c00..6bbb63d 100644 --- a/Code/Car/VeloXCar.cs +++ b/Code/Car/VeloXCar.cs @@ -7,17 +7,11 @@ namespace 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 ) + StreamPlayer = new( Stream ); + if ( IsDriver ) { UpdateGearList(); UpdatePowerDistribution(); @@ -35,26 +29,24 @@ public partial class VeloXCar : VeloXBase StreamPlayer.EngineState = EngineState; StreamPlayer.IsRedlining = IsRedlining; - if ( Driver.IsValid() && Driver.IsProxy ) - StreamPlayer.Update( Time.Delta, Scene.Camera.WorldPosition ); - else - StreamPlayer.Update( Time.Delta, WorldPosition ); + StreamPlayer.Update( Time.Delta, WorldPosition ); } } protected override void OnFixedUpdate() { - if ( IsProxy ) + if ( !IsDriver ) return; base.OnFixedUpdate(); + Brake = Math.Clamp( frontBrake + rearBrake + (Input.Down( "Jump" ) ? 1 : 0), 0, 1 ); + var dt = Time.Delta; EngineThink( dt ); WheelThink( dt ); UpdateSteering( dt ); - Brake = Math.Clamp( frontBrake + rearBrake + (Input.Down( "Jump" ) ? 1 : 0), 0, 1 ); } }