Path: blob/master/thirdparty/jolt_physics/Jolt/Physics/Vehicle/WheeledVehicleController.cpp
9912 views
// Jolt Physics Library (https://github.com/jrouwe/JoltPhysics)1// SPDX-FileCopyrightText: 2021 Jorrit Rouwe2// SPDX-License-Identifier: MIT34#include <Jolt/Jolt.h>56#include <Jolt/Physics/Vehicle/WheeledVehicleController.h>7#include <Jolt/Physics/PhysicsSystem.h>8#include <Jolt/ObjectStream/TypeDeclarations.h>9#include <Jolt/Core/StreamIn.h>10#include <Jolt/Core/StreamOut.h>11#include <Jolt/Math/DynMatrix.h>12#include <Jolt/Math/GaussianElimination.h>13#ifdef JPH_DEBUG_RENDERER14#include <Jolt/Renderer/DebugRenderer.h>15#endif // JPH_DEBUG_RENDERER1617//#define JPH_TRACE_VEHICLE_STATS1819JPH_NAMESPACE_BEGIN2021JPH_IMPLEMENT_SERIALIZABLE_VIRTUAL(WheeledVehicleControllerSettings)22{23JPH_ADD_BASE_CLASS(WheeledVehicleControllerSettings, VehicleControllerSettings)2425JPH_ADD_ATTRIBUTE(WheeledVehicleControllerSettings, mEngine)26JPH_ADD_ATTRIBUTE(WheeledVehicleControllerSettings, mTransmission)27JPH_ADD_ATTRIBUTE(WheeledVehicleControllerSettings, mDifferentials)28JPH_ADD_ATTRIBUTE(WheeledVehicleControllerSettings, mDifferentialLimitedSlipRatio)29}3031JPH_IMPLEMENT_SERIALIZABLE_VIRTUAL(WheelSettingsWV)32{33JPH_ADD_ATTRIBUTE(WheelSettingsWV, mInertia)34JPH_ADD_ATTRIBUTE(WheelSettingsWV, mAngularDamping)35JPH_ADD_ATTRIBUTE(WheelSettingsWV, mMaxSteerAngle)36JPH_ADD_ATTRIBUTE(WheelSettingsWV, mLongitudinalFriction)37JPH_ADD_ATTRIBUTE(WheelSettingsWV, mLateralFriction)38JPH_ADD_ATTRIBUTE(WheelSettingsWV, mMaxBrakeTorque)39JPH_ADD_ATTRIBUTE(WheelSettingsWV, mMaxHandBrakeTorque)40}4142WheelSettingsWV::WheelSettingsWV()43{44mLongitudinalFriction.Reserve(3);45mLongitudinalFriction.AddPoint(0.0f, 0.0f);46mLongitudinalFriction.AddPoint(0.06f, 1.2f);47mLongitudinalFriction.AddPoint(0.2f, 1.0f);4849mLateralFriction.Reserve(3);50mLateralFriction.AddPoint(0.0f, 0.0f);51mLateralFriction.AddPoint(3.0f, 1.2f);52mLateralFriction.AddPoint(20.0f, 1.0f);53}5455void WheelSettingsWV::SaveBinaryState(StreamOut &inStream) const56{57inStream.Write(mInertia);58inStream.Write(mAngularDamping);59inStream.Write(mMaxSteerAngle);60mLongitudinalFriction.SaveBinaryState(inStream);61mLateralFriction.SaveBinaryState(inStream);62inStream.Write(mMaxBrakeTorque);63inStream.Write(mMaxHandBrakeTorque);64}6566void WheelSettingsWV::RestoreBinaryState(StreamIn &inStream)67{68inStream.Read(mInertia);69inStream.Read(mAngularDamping);70inStream.Read(mMaxSteerAngle);71mLongitudinalFriction.RestoreBinaryState(inStream);72mLateralFriction.RestoreBinaryState(inStream);73inStream.Read(mMaxBrakeTorque);74inStream.Read(mMaxHandBrakeTorque);75}7677WheelWV::WheelWV(const WheelSettingsWV &inSettings) :78Wheel(inSettings)79{80JPH_ASSERT(inSettings.mInertia >= 0.0f);81JPH_ASSERT(inSettings.mAngularDamping >= 0.0f);82JPH_ASSERT(abs(inSettings.mMaxSteerAngle) <= 0.5f * JPH_PI);83JPH_ASSERT(inSettings.mMaxBrakeTorque >= 0.0f);84JPH_ASSERT(inSettings.mMaxHandBrakeTorque >= 0.0f);85}8687void WheelWV::Update(uint inWheelIndex, float inDeltaTime, const VehicleConstraint &inConstraint)88{89const WheelSettingsWV *settings = GetSettings();9091// Angular damping: dw/dt = -c * w92// Solution: w(t) = w(0) * e^(-c * t) or w2 = w1 * e^(-c * dt)93// Taylor expansion of e^(-c * dt) = 1 - c * dt + ...94// Since dt is usually in the order of 1/60 and c is a low number too this approximation is good enough95mAngularVelocity *= max(0.0f, 1.0f - settings->mAngularDamping * inDeltaTime);9697// Update rotation of wheel98mAngle = fmod(mAngle + mAngularVelocity * inDeltaTime, 2.0f * JPH_PI);99100if (mContactBody != nullptr)101{102const Body *body = inConstraint.GetVehicleBody();103104// Calculate relative velocity between wheel contact point and floor105Vec3 relative_velocity = body->GetPointVelocity(mContactPosition) - mContactPointVelocity;106107// Cancel relative velocity in the normal plane108relative_velocity -= mContactNormal.Dot(relative_velocity) * mContactNormal;109float relative_longitudinal_velocity = relative_velocity.Dot(mContactLongitudinal);110111// Calculate longitudinal friction based on difference between velocity of rolling wheel and drive surface112float relative_longitudinal_velocity_denom = Sign(relative_longitudinal_velocity) * max(1.0e-3f, abs(relative_longitudinal_velocity)); // Ensure we don't divide by zero113mLongitudinalSlip = abs((mAngularVelocity * settings->mRadius - relative_longitudinal_velocity) / relative_longitudinal_velocity_denom);114float longitudinal_slip_friction = settings->mLongitudinalFriction.GetValue(mLongitudinalSlip);115116// Calculate lateral friction based on slip angle117float relative_velocity_len = relative_velocity.Length();118mLateralSlip = relative_velocity_len < 1.0e-3f ? 0.0f : ACos(abs(relative_longitudinal_velocity) / relative_velocity_len);119float lateral_slip_angle = RadiansToDegrees(mLateralSlip);120float lateral_slip_friction = settings->mLateralFriction.GetValue(lateral_slip_angle);121122// Tire friction123VehicleConstraint::CombineFunction combine_friction = inConstraint.GetCombineFriction();124mCombinedLongitudinalFriction = longitudinal_slip_friction;125mCombinedLateralFriction = lateral_slip_friction;126combine_friction(inWheelIndex, mCombinedLongitudinalFriction, mCombinedLateralFriction, *mContactBody, mContactSubShapeID);127}128else129{130// No collision131mLongitudinalSlip = 0.0f;132mLateralSlip = 0.0f;133mCombinedLongitudinalFriction = mCombinedLateralFriction = 0.0f;134}135}136137VehicleController *WheeledVehicleControllerSettings::ConstructController(VehicleConstraint &inConstraint) const138{139return new WheeledVehicleController(*this, inConstraint);140}141142void WheeledVehicleControllerSettings::SaveBinaryState(StreamOut &inStream) const143{144mEngine.SaveBinaryState(inStream);145146mTransmission.SaveBinaryState(inStream);147148uint32 num_differentials = (uint32)mDifferentials.size();149inStream.Write(num_differentials);150for (const VehicleDifferentialSettings &d : mDifferentials)151d.SaveBinaryState(inStream);152153inStream.Write(mDifferentialLimitedSlipRatio);154}155156void WheeledVehicleControllerSettings::RestoreBinaryState(StreamIn &inStream)157{158mEngine.RestoreBinaryState(inStream);159160mTransmission.RestoreBinaryState(inStream);161162uint32 num_differentials = 0;163inStream.Read(num_differentials);164mDifferentials.resize(num_differentials);165for (VehicleDifferentialSettings &d : mDifferentials)166d.RestoreBinaryState(inStream);167168inStream.Read(mDifferentialLimitedSlipRatio);169}170171WheeledVehicleController::WheeledVehicleController(const WheeledVehicleControllerSettings &inSettings, VehicleConstraint &inConstraint) :172VehicleController(inConstraint)173{174// Copy engine settings175static_cast<VehicleEngineSettings &>(mEngine) = inSettings.mEngine;176JPH_ASSERT(inSettings.mEngine.mMinRPM >= 0.0f);177JPH_ASSERT(inSettings.mEngine.mMinRPM <= inSettings.mEngine.mMaxRPM);178mEngine.SetCurrentRPM(mEngine.mMinRPM);179180// Copy transmission settings181static_cast<VehicleTransmissionSettings &>(mTransmission) = inSettings.mTransmission;182#ifdef JPH_ENABLE_ASSERTS183for (float r : inSettings.mTransmission.mGearRatios)184JPH_ASSERT(r > 0.0f);185for (float r : inSettings.mTransmission.mReverseGearRatios)186JPH_ASSERT(r < 0.0f);187#endif // JPH_ENABLE_ASSERTS188JPH_ASSERT(inSettings.mTransmission.mSwitchTime >= 0.0f);189JPH_ASSERT(inSettings.mTransmission.mShiftDownRPM > 0.0f);190JPH_ASSERT(inSettings.mTransmission.mMode != ETransmissionMode::Auto || inSettings.mTransmission.mShiftUpRPM < inSettings.mEngine.mMaxRPM);191JPH_ASSERT(inSettings.mTransmission.mShiftUpRPM > inSettings.mTransmission.mShiftDownRPM);192JPH_ASSERT(inSettings.mTransmission.mClutchStrength > 0.0f);193194// Copy differential settings195mDifferentials.resize(inSettings.mDifferentials.size());196for (uint i = 0; i < mDifferentials.size(); ++i)197{198const VehicleDifferentialSettings &d = inSettings.mDifferentials[i];199mDifferentials[i] = d;200JPH_ASSERT(d.mDifferentialRatio > 0.0f);201JPH_ASSERT(d.mLeftRightSplit >= 0.0f && d.mLeftRightSplit <= 1.0f);202JPH_ASSERT(d.mEngineTorqueRatio >= 0.0f);203JPH_ASSERT(d.mLimitedSlipRatio > 1.0f);204}205206mDifferentialLimitedSlipRatio = inSettings.mDifferentialLimitedSlipRatio;207JPH_ASSERT(mDifferentialLimitedSlipRatio > 1.0f);208}209210float WheeledVehicleController::GetWheelSpeedAtClutch() const211{212float wheel_speed_at_clutch = 0.0f;213int num_driven_wheels = 0;214for (const VehicleDifferentialSettings &d : mDifferentials)215{216int wheels[] = { d.mLeftWheel, d.mRightWheel };217for (int w : wheels)218if (w >= 0)219{220wheel_speed_at_clutch += mConstraint.GetWheel(w)->GetAngularVelocity() * d.mDifferentialRatio;221num_driven_wheels++;222}223}224return wheel_speed_at_clutch / float(num_driven_wheels) * VehicleEngine::cAngularVelocityToRPM * mTransmission.GetCurrentRatio();225}226227bool WheeledVehicleController::AllowSleep() const228{229return mForwardInput == 0.0f // No user input230&& mTransmission.AllowSleep() // Transmission is not shifting231&& mEngine.AllowSleep(); // Engine is idling232}233234void WheeledVehicleController::PreCollide(float inDeltaTime, PhysicsSystem &inPhysicsSystem)235{236JPH_PROFILE_FUNCTION();237238#ifdef JPH_TRACE_VEHICLE_STATS239static bool sTracedHeader = false;240if (!sTracedHeader)241{242Trace("Time, ForwardInput, Gear, ClutchFriction, EngineRPM, WheelRPM, Velocity (km/h)");243sTracedHeader = true;244}245static float sTime = 0.0f;246sTime += inDeltaTime;247Trace("%.3f, %.1f, %d, %.1f, %.1f, %.1f, %.1f", sTime, mForwardInput, mTransmission.GetCurrentGear(), mTransmission.GetClutchFriction(), mEngine.GetCurrentRPM(), GetWheelSpeedAtClutch(), mConstraint.GetVehicleBody()->GetLinearVelocity().Length() * 3.6f);248#endif // JPH_TRACE_VEHICLE_STATS249250for (Wheel *w_base : mConstraint.GetWheels())251{252WheelWV *w = static_cast<WheelWV *>(w_base);253254// Set steering angle255w->SetSteerAngle(-mRightInput * w->GetSettings()->mMaxSteerAngle);256}257}258259void WheeledVehicleController::PostCollide(float inDeltaTime, PhysicsSystem &inPhysicsSystem)260{261JPH_PROFILE_FUNCTION();262263// Remember old RPM so we can detect if we're increasing or decreasing264float old_engine_rpm = mEngine.GetCurrentRPM();265266Wheels &wheels = mConstraint.GetWheels();267268// Update wheel angle, do this before applying torque to the wheels (as friction will slow them down again)269for (uint wheel_index = 0, num_wheels = (uint)wheels.size(); wheel_index < num_wheels; ++wheel_index)270{271WheelWV *w = static_cast<WheelWV *>(wheels[wheel_index]);272w->Update(wheel_index, inDeltaTime, mConstraint);273}274275// In auto transmission mode, don't accelerate the engine when switching gears276float forward_input = abs(mForwardInput);277if (mTransmission.mMode == ETransmissionMode::Auto)278forward_input *= mTransmission.GetClutchFriction();279280// Apply engine damping281mEngine.ApplyDamping(inDeltaTime);282283// Calculate engine torque284float engine_torque = mEngine.GetTorque(forward_input);285286// Define a struct that contains information about driven differentials (i.e. that have wheels connected)287struct DrivenDifferential288{289const VehicleDifferentialSettings * mDifferential;290float mAngularVelocity;291float mClutchToDifferentialTorqueRatio;292float mTempTorqueFactor;293};294295// Collect driven differentials and their speeds296Array<DrivenDifferential> driven_differentials;297driven_differentials.reserve(mDifferentials.size());298float differential_omega_min = FLT_MAX, differential_omega_max = 0.0f;299for (const VehicleDifferentialSettings &d : mDifferentials)300{301float avg_omega = 0.0f;302int avg_omega_denom = 0;303int indices[] = { d.mLeftWheel, d.mRightWheel };304for (int idx : indices)305if (idx != -1)306{307avg_omega += wheels[idx]->GetAngularVelocity();308avg_omega_denom++;309}310311if (avg_omega_denom > 0)312{313avg_omega = abs(avg_omega * d.mDifferentialRatio / float(avg_omega_denom)); // ignoring that the differentials may be rotating in different directions314driven_differentials.push_back({ &d, avg_omega, d.mEngineTorqueRatio, 0 });315316// Remember min and max velocity317differential_omega_min = min(differential_omega_min, avg_omega);318differential_omega_max = max(differential_omega_max, avg_omega);319}320}321322if (mDifferentialLimitedSlipRatio < FLT_MAX // Limited slip differential needs to be turned on323&& differential_omega_max > differential_omega_min) // There needs to be a velocity difference324{325// Calculate factor based on relative speed of a differential326float sum_factor = 0.0f;327for (DrivenDifferential &d : driven_differentials)328{329// Differential with max velocity gets factor 0, differential with min velocity 1330d.mTempTorqueFactor = (differential_omega_max - d.mAngularVelocity) / (differential_omega_max - differential_omega_min);331sum_factor += d.mTempTorqueFactor;332}333334// Normalize the result335for (DrivenDifferential &d : driven_differentials)336d.mTempTorqueFactor /= sum_factor;337338// Prevent div by zero339differential_omega_min = max(1.0e-3f, differential_omega_min);340differential_omega_max = max(1.0e-3f, differential_omega_max);341342// Map into a value that is 0 when the wheels are turning at an equal rate and 1 when the wheels are turning at mDifferentialLimitedSlipRatio343float alpha = min((differential_omega_max / differential_omega_min - 1.0f) / (mDifferentialLimitedSlipRatio - 1.0f), 1.0f);344JPH_ASSERT(alpha >= 0.0f);345float one_min_alpha = 1.0f - alpha;346347// Update torque ratio for all differentials348for (DrivenDifferential &d : driven_differentials)349d.mClutchToDifferentialTorqueRatio = one_min_alpha * d.mClutchToDifferentialTorqueRatio + alpha * d.mTempTorqueFactor;350}351352#ifdef JPH_ENABLE_ASSERTS353// Assert the values add up to 1354float sum_torque_factors = 0.0f;355for (DrivenDifferential &d : driven_differentials)356sum_torque_factors += d.mClutchToDifferentialTorqueRatio;357JPH_ASSERT(abs(sum_torque_factors - 1.0f) < 1.0e-6f);358#endif // JPH_ENABLE_ASSERTS359360// Define a struct that collects information about the wheels that connect to the engine361struct DrivenWheel362{363WheelWV * mWheel;364float mClutchToWheelRatio;365float mClutchToWheelTorqueRatio;366float mEstimatedAngularImpulse;367};368Array<DrivenWheel> driven_wheels;369driven_wheels.reserve(wheels.size());370371// Collect driven wheels372float transmission_ratio = mTransmission.GetCurrentRatio();373for (const DrivenDifferential &dd : driven_differentials)374{375VehicleDifferentialSettings d = *dd.mDifferential;376377WheelWV *wl = d.mLeftWheel != -1? static_cast<WheelWV *>(wheels[d.mLeftWheel]) : nullptr;378WheelWV *wr = d.mRightWheel != -1? static_cast<WheelWV *>(wheels[d.mRightWheel]) : nullptr;379380float clutch_to_wheel_ratio = transmission_ratio * d.mDifferentialRatio;381382if (wl != nullptr && wr != nullptr)383{384// Calculate torque ratio385float ratio_l, ratio_r;386d.CalculateTorqueRatio(wl->GetAngularVelocity(), wr->GetAngularVelocity(), ratio_l, ratio_r);387388// Add both wheels389driven_wheels.push_back({ wl, clutch_to_wheel_ratio, dd.mClutchToDifferentialTorqueRatio * ratio_l, 0.0f });390driven_wheels.push_back({ wr, clutch_to_wheel_ratio, dd.mClutchToDifferentialTorqueRatio * ratio_r, 0.0f });391}392else if (wl != nullptr)393{394// Only left wheel, all power to left395driven_wheels.push_back({ wl, clutch_to_wheel_ratio, dd.mClutchToDifferentialTorqueRatio, 0.0f });396}397else if (wr != nullptr)398{399// Only right wheel, all power to right400driven_wheels.push_back({ wr, clutch_to_wheel_ratio, dd.mClutchToDifferentialTorqueRatio, 0.0f });401}402}403404bool solved = false;405if (!driven_wheels.empty())406{407// Define the torque at the clutch at time t as:408//409// tc(t):=S*(we(t)-sum(R(j)*ww(j,t),j,1,N)/N)410//411// Where:412// S is the total strength of clutch (= friction * strength)413// we(t) is the engine angular velocity at time t414// R(j) is the total gear ratio of clutch to wheel for wheel j415// ww(j,t) is the angular velocity of wheel j at time t416// N is the amount of wheels417//418// The torque that increases the engine angular velocity at time t is:419//420// te(t):=TE-tc(t)421//422// Where:423// TE is the torque delivered by the engine424//425// The torque that increases the wheel angular velocity for wheel i at time t is:426//427// tw(i,t):=TW(i)+R(i)*F(i)*tc(t)428//429// Where:430// TW(i) is the torque applied to the wheel outside of the engine (brake + torque due to friction with the ground)431// F(i) is the fraction of the engine torque applied from engine to wheel i432//433// Because the angular acceleration and torque are connected through: Torque = I * dw/dt434//435// We have the angular acceleration of the engine at time t:436//437// ddt_we(t):=te(t)/Ie438//439// Where:440// Ie is the inertia of the engine441//442// We have the angular acceleration of wheel i at time t:443//444// ddt_ww(i,t):=tw(i,t)/Iw(i)445//446// Where:447// Iw(i) is the inertia of wheel i448//449// We could take a simple Euler step to calculate the resulting accelerations but because the system is very stiff this turns out to be unstable, so we need to use implicit Euler instead:450//451// we(t+dt)=we(t)+dt*ddt_we(t+dt)452//453// and:454//455// ww(i,t+dt)=ww(i,t)+dt*ddt_ww(i,t+dt)456//457// Expanding both equations (the equations above are in wxMaxima format and this can easily be done by expand(%)):458//459// For wheel:460//461// ww(i,t+dt) + (S*dt*F(i)*R(i)*sum(R(j)*ww(j,t+dt),j,1,N))/(N*Iw(i)) - (S*dt*F(i)*R(i)*we(t+dt))/Iw(i) = ww(i,t)+(dt*TW(i))/Iw(i)462//463// For engine:464//465// we(t+dt) + (S*dt*we(t+dt))/Ie - (S*dt*sum(R(j)*ww(j,t+dt),j,1,N))/(Ie*N) = we(t)+(TE*dt)/Ie466//467// Defining a vector w(t) = (ww(1, t), ww(2, t), ..., ww(N, t), we(t)) we can write both equations as a matrix multiplication:468//469// a * w(t + dt) = b470//471// We then invert the matrix to get the new angular velocities.472473// Dimension of matrix is N + 1474int n = (int)driven_wheels.size() + 1;475476// Last column of w is for the engine angular velocity477int engine = n - 1;478479// Define a and b480DynMatrix a(n, n);481DynMatrix b(n, 1);482483// Get number of driven wheels as a float484float num_driven_wheels_float = float(driven_wheels.size());485486// Angular velocity of engine487float w_engine = mEngine.GetAngularVelocity();488489// Calculate the total strength of the clutch490float clutch_strength = transmission_ratio != 0.0f? mTransmission.GetClutchFriction() * mTransmission.mClutchStrength : 0.0f;491492// dt / Ie493float dt_div_ie = inDeltaTime / mEngine.mInertia;494495// Calculate scale factor for impulses based on previous delta time496float impulse_scale = mPreviousDeltaTime > 0.0f? inDeltaTime / mPreviousDeltaTime : 0.0f;497498// Iterate the rows for the wheels499for (int i = 0; i < (int)driven_wheels.size(); ++i)500{501DrivenWheel &w_i = driven_wheels[i];502const WheelSettingsWV *settings = w_i.mWheel->GetSettings();503504// Get wheel inertia505float inertia = settings->mInertia;506507// S * R(i)508float s_r = clutch_strength * w_i.mClutchToWheelRatio;509510// dt * S * R(i) * F(i) / Iw511float dt_s_r_f_div_iw = inDeltaTime * s_r * w_i.mClutchToWheelTorqueRatio / inertia;512513// Fill in the columns of a for wheel j514for (int j = 0; j < (int)driven_wheels.size(); ++j)515{516const DrivenWheel &w_j = driven_wheels[j];517a(i, j) = dt_s_r_f_div_iw * w_j.mClutchToWheelRatio / num_driven_wheels_float;518}519520// Add ww(i, t+dt)521a(i, i) += 1.0f;522523// Add the column for the engine524a(i, engine) = -dt_s_r_f_div_iw;525526// Calculate external angular impulse operating on the wheel: TW(i) * dt527float dt_tw = 0.0f;528529// Combine brake with hand brake torque530float brake_torque = mBrakeInput * settings->mMaxBrakeTorque + mHandBrakeInput * settings->mMaxHandBrakeTorque;531if (brake_torque > 0.0f)532{533// We're braking534// Calculate brake angular impulse535float sign;536if (w_i.mWheel->GetAngularVelocity() != 0.0f)537sign = Sign(w_i.mWheel->GetAngularVelocity());538else539sign = Sign(mTransmission.GetCurrentRatio()); // When wheels have locked up use the transmission ratio to determine the sign540dt_tw = sign * inDeltaTime * brake_torque;541}542543if (w_i.mWheel->HasContact())544{545// We have wheel contact with the floor546// Note that we don't know the torque due to the ground contact yet, so we use the impulse applied from the last frame to estimate it547// Wheel torque TW = force * radius = lambda / dt * radius548dt_tw += impulse_scale * w_i.mWheel->GetLongitudinalLambda() * settings->mRadius;549}550551w_i.mEstimatedAngularImpulse = dt_tw;552553// Fill in the constant b = ww(i,t)+(dt*TW(i))/Iw(i)554b(i, 0) = w_i.mWheel->GetAngularVelocity() - dt_tw / inertia;555556// To avoid looping over the wheels again, we also fill in the wheel columns of the engine row here557a(engine, i) = -dt_div_ie * s_r / num_driven_wheels_float;558}559560// Finalize the engine row561a(engine, engine) = (1.0f + dt_div_ie * clutch_strength);562b(engine, 0) = w_engine + dt_div_ie * engine_torque;563564// Solve the linear equation565if (GaussianElimination(a, b))566{567// Update the angular velocities for the wheels568for (int i = 0; i < (int)driven_wheels.size(); ++i)569{570DrivenWheel &w_i = driven_wheels[i];571const WheelSettingsWV *settings = w_i.mWheel->GetSettings();572573// Get solved wheel angular velocity574float angular_velocity = b(i, 0);575576// We estimated TW and applied it in the equation above, but we haven't actually applied this torque yet so we undo it here.577// It will be applied when we solve the actual braking / the constraints with the floor.578angular_velocity += w_i.mEstimatedAngularImpulse / settings->mInertia;579580// Update angular velocity581w_i.mWheel->SetAngularVelocity(angular_velocity);582}583584// Update the engine RPM585mEngine.SetCurrentRPM(b(engine, 0) * VehicleEngine::cAngularVelocityToRPM);586587// The speeds have been solved588solved = true;589}590else591{592JPH_ASSERT(false, "New engine/wheel speeds could not be calculated!");593}594}595596if (!solved)597{598// Engine not connected to wheels, apply all torque to engine rotation599mEngine.ApplyTorque(engine_torque, inDeltaTime);600}601602// Calculate if any of the wheels are slipping, this is used to prevent gear switching603bool wheels_slipping = false;604for (const DrivenWheel &w : driven_wheels)605wheels_slipping |= w.mClutchToWheelTorqueRatio > 0.0f && (!w.mWheel->HasContact() || w.mWheel->mLongitudinalSlip > 0.1f);606607// Only allow shifting up when we're not slipping and we're increasing our RPM.608// After a jump, we have a very high engine RPM but once we hit the ground the RPM should be decreasing and we don't want to shift up609// during that time.610bool can_shift_up = !wheels_slipping && mEngine.GetCurrentRPM() >= old_engine_rpm;611612// Update transmission613mTransmission.Update(inDeltaTime, mEngine.GetCurrentRPM(), mForwardInput, can_shift_up);614615// Braking616for (Wheel *w_base : wheels)617{618WheelWV *w = static_cast<WheelWV *>(w_base);619const WheelSettingsWV *settings = w->GetSettings();620621// Combine brake with hand brake torque622float brake_torque = mBrakeInput * settings->mMaxBrakeTorque + mHandBrakeInput * settings->mMaxHandBrakeTorque;623if (brake_torque > 0.0f)624{625// Calculate how much torque is needed to stop the wheels from rotating in this time step626float brake_torque_to_lock_wheels = abs(w->GetAngularVelocity()) * settings->mInertia / inDeltaTime;627if (brake_torque > brake_torque_to_lock_wheels)628{629// Wheels are locked630w->SetAngularVelocity(0.0f);631w->mBrakeImpulse = (brake_torque - brake_torque_to_lock_wheels) * inDeltaTime / settings->mRadius;632}633else634{635// Slow down the wheels636w->ApplyTorque(-Sign(w->GetAngularVelocity()) * brake_torque, inDeltaTime);637w->mBrakeImpulse = 0.0f;638}639}640else641{642// Not braking643w->mBrakeImpulse = 0.0f;644}645}646647// Remember previous delta time so we can scale the impulses correctly648mPreviousDeltaTime = inDeltaTime;649}650651bool WheeledVehicleController::SolveLongitudinalAndLateralConstraints(float inDeltaTime)652{653bool impulse = false;654655float *max_lateral_friction_impulse = (float *)JPH_STACK_ALLOC(mConstraint.GetWheels().size() * sizeof(float));656657uint wheel_index = 0;658for (Wheel *w_base : mConstraint.GetWheels())659{660if (w_base->HasContact())661{662WheelWV *w = static_cast<WheelWV *>(w_base);663const WheelSettingsWV *settings = w->GetSettings();664665// Calculate max impulse that we can apply on the ground666float max_longitudinal_friction_impulse;667mTireMaxImpulseCallback(wheel_index,668max_longitudinal_friction_impulse, max_lateral_friction_impulse[wheel_index], w->GetSuspensionLambda(),669w->mCombinedLongitudinalFriction, w->mCombinedLateralFriction, w->mLongitudinalSlip, w->mLateralSlip, inDeltaTime);670671// Calculate relative velocity between wheel contact point and floor in longitudinal direction672Vec3 relative_velocity = mConstraint.GetVehicleBody()->GetPointVelocity(w->GetContactPosition()) - w->GetContactPointVelocity();673float relative_longitudinal_velocity = relative_velocity.Dot(w->GetContactLongitudinal());674675// Calculate brake force to apply676float min_longitudinal_impulse, max_longitudinal_impulse;677if (w->mBrakeImpulse != 0.0f)678{679// Limit brake force by max tire friction680float brake_impulse = min(w->mBrakeImpulse, max_longitudinal_friction_impulse);681682// Check which direction the brakes should be applied (we don't want to apply an impulse that would accelerate the vehicle)683if (relative_longitudinal_velocity >= 0.0f)684{685min_longitudinal_impulse = -brake_impulse;686max_longitudinal_impulse = 0.0f;687}688else689{690min_longitudinal_impulse = 0.0f;691max_longitudinal_impulse = brake_impulse;692}693694// Longitudinal impulse, note that we assume that once the wheels are locked that the brakes have more than enough torque to keep the wheels locked so we exclude any rotation deltas695impulse |= w->SolveLongitudinalConstraintPart(mConstraint, min_longitudinal_impulse, max_longitudinal_impulse);696}697else698{699// Assume we want to apply an angular impulse that makes the delta velocity between wheel and ground zero in one time step, calculate the amount of linear impulse needed to do that700float desired_angular_velocity = relative_longitudinal_velocity / settings->mRadius;701float linear_impulse = (w->GetAngularVelocity() - desired_angular_velocity) * settings->mInertia / settings->mRadius;702703// Limit the impulse by max tire friction704float prev_lambda = w->GetLongitudinalLambda();705min_longitudinal_impulse = max_longitudinal_impulse = Clamp(prev_lambda + linear_impulse, -max_longitudinal_friction_impulse, max_longitudinal_friction_impulse);706707// Longitudinal impulse708impulse |= w->SolveLongitudinalConstraintPart(mConstraint, min_longitudinal_impulse, max_longitudinal_impulse);709710// Update the angular velocity of the wheels according to the lambda that was applied711w->SetAngularVelocity(w->GetAngularVelocity() - (w->GetLongitudinalLambda() - prev_lambda) * settings->mRadius / settings->mInertia);712}713}714++wheel_index;715}716717wheel_index = 0;718for (Wheel *w_base : mConstraint.GetWheels())719{720if (w_base->HasContact())721{722WheelWV *w = static_cast<WheelWV *>(w_base);723724// Lateral friction725float max_lateral_impulse = max_lateral_friction_impulse[wheel_index];726impulse |= w->SolveLateralConstraintPart(mConstraint, -max_lateral_impulse, max_lateral_impulse);727}728++wheel_index;729}730731return impulse;732}733734#ifdef JPH_DEBUG_RENDERER735736void WheeledVehicleController::Draw(DebugRenderer *inRenderer) const737{738float constraint_size = mConstraint.GetDrawConstraintSize();739740// Draw RPM741Body *body = mConstraint.GetVehicleBody();742Vec3 rpm_meter_up = body->GetRotation() * mConstraint.GetLocalUp();743RVec3 rpm_meter_pos = body->GetPosition() + body->GetRotation() * mRPMMeterPosition;744Vec3 rpm_meter_fwd = body->GetRotation() * mConstraint.GetLocalForward();745mEngine.DrawRPM(inRenderer, rpm_meter_pos, rpm_meter_fwd, rpm_meter_up, mRPMMeterSize, mTransmission.mShiftDownRPM, mTransmission.mShiftUpRPM);746747if (mTransmission.GetCurrentRatio() != 0.0f)748{749// Calculate average wheel speed at clutch750float wheel_speed_at_clutch = GetWheelSpeedAtClutch();751752// Draw the average wheel speed measured at clutch to compare engine RPM with wheel RPM753inRenderer->DrawLine(rpm_meter_pos, rpm_meter_pos + Quat::sRotation(rpm_meter_fwd, mEngine.ConvertRPMToAngle(wheel_speed_at_clutch)) * (rpm_meter_up * 1.1f * mRPMMeterSize), Color::sYellow);754}755756// Draw current vehicle state757String status = StringFormat("Forward: %.1f, Right: %.1f\nBrake: %.1f, HandBrake: %.1f\n"758"Gear: %d, Clutch: %.1f\nEngineRPM: %.0f, V: %.1f km/h",759(double)mForwardInput, (double)mRightInput, (double)mBrakeInput, (double)mHandBrakeInput,760mTransmission.GetCurrentGear(), (double)mTransmission.GetClutchFriction(), (double)mEngine.GetCurrentRPM(), (double)body->GetLinearVelocity().Length() * 3.6);761inRenderer->DrawText3D(body->GetPosition(), status, Color::sWhite, constraint_size);762763RMat44 body_transform = body->GetWorldTransform();764765for (const Wheel *w_base : mConstraint.GetWheels())766{767const WheelWV *w = static_cast<const WheelWV *>(w_base);768const WheelSettings *settings = w->GetSettings();769770// Calculate where the suspension attaches to the body in world space771RVec3 ws_position = body_transform * settings->mPosition;772Vec3 ws_direction = body_transform.Multiply3x3(settings->mSuspensionDirection);773774// Draw suspension775RVec3 min_suspension_pos = ws_position + ws_direction * settings->mSuspensionMinLength;776RVec3 max_suspension_pos = ws_position + ws_direction * settings->mSuspensionMaxLength;777inRenderer->DrawLine(ws_position, min_suspension_pos, Color::sRed);778inRenderer->DrawLine(min_suspension_pos, max_suspension_pos, Color::sGreen);779780// Draw current length781RVec3 wheel_pos = ws_position + ws_direction * w->GetSuspensionLength();782inRenderer->DrawMarker(wheel_pos, w->GetSuspensionLength() < settings->mSuspensionMinLength? Color::sRed : Color::sGreen, constraint_size);783784// Draw wheel basis785Vec3 wheel_forward, wheel_up, wheel_right;786mConstraint.GetWheelLocalBasis(w, wheel_forward, wheel_up, wheel_right);787wheel_forward = body_transform.Multiply3x3(wheel_forward);788wheel_up = body_transform.Multiply3x3(wheel_up);789wheel_right = body_transform.Multiply3x3(wheel_right);790Vec3 steering_axis = body_transform.Multiply3x3(settings->mSteeringAxis);791inRenderer->DrawLine(wheel_pos, wheel_pos + wheel_forward, Color::sRed);792inRenderer->DrawLine(wheel_pos, wheel_pos + wheel_up, Color::sGreen);793inRenderer->DrawLine(wheel_pos, wheel_pos + wheel_right, Color::sBlue);794inRenderer->DrawLine(wheel_pos, wheel_pos + steering_axis, Color::sYellow);795796// Draw wheel797RMat44 wheel_transform(Vec4(wheel_up, 0.0f), Vec4(wheel_right, 0.0f), Vec4(wheel_forward, 0.0f), wheel_pos);798wheel_transform.SetRotation(wheel_transform.GetRotation() * Mat44::sRotationY(-w->GetRotationAngle()));799inRenderer->DrawCylinder(wheel_transform, settings->mWidth * 0.5f, settings->mRadius, w->GetSuspensionLength() <= settings->mSuspensionMinLength? Color::sRed : Color::sGreen, DebugRenderer::ECastShadow::Off, DebugRenderer::EDrawMode::Wireframe);800801if (w->HasContact())802{803// Draw contact804inRenderer->DrawLine(w->GetContactPosition(), w->GetContactPosition() + w->GetContactNormal(), Color::sYellow);805inRenderer->DrawLine(w->GetContactPosition(), w->GetContactPosition() + w->GetContactLongitudinal(), Color::sRed);806inRenderer->DrawLine(w->GetContactPosition(), w->GetContactPosition() + w->GetContactLateral(), Color::sBlue);807808DebugRenderer::sInstance->DrawText3D(wheel_pos, StringFormat("W: %.1f, S: %.2f\nSlipLateral: %.1f, SlipLong: %.2f\nFrLateral: %.1f, FrLong: %.1f", (double)w->GetAngularVelocity(), (double)w->GetSuspensionLength(), (double)RadiansToDegrees(w->mLateralSlip), (double)w->mLongitudinalSlip, (double)w->mCombinedLateralFriction, (double)w->mCombinedLongitudinalFriction), Color::sWhite, constraint_size);809}810else811{812// Draw 'no hit'813DebugRenderer::sInstance->DrawText3D(wheel_pos, StringFormat("W: %.1f", (double)w->GetAngularVelocity()), Color::sRed, constraint_size);814}815}816}817818#endif // JPH_DEBUG_RENDERER819820void WheeledVehicleController::SaveState(StateRecorder &inStream) const821{822inStream.Write(mForwardInput);823inStream.Write(mRightInput);824inStream.Write(mBrakeInput);825inStream.Write(mHandBrakeInput);826inStream.Write(mPreviousDeltaTime);827828mEngine.SaveState(inStream);829mTransmission.SaveState(inStream);830}831832void WheeledVehicleController::RestoreState(StateRecorder &inStream)833{834inStream.Read(mForwardInput);835inStream.Read(mRightInput);836inStream.Read(mBrakeInput);837inStream.Read(mHandBrakeInput);838inStream.Read(mPreviousDeltaTime);839840mEngine.RestoreState(inStream);841mTransmission.RestoreState(inStream);842}843844JPH_NAMESPACE_END845846847