Browse Source

Added vehicle callbacks (#681)

* Added vehicle callbacks at the beginning of the step listener and after wheel checks
* Added ability to read out lateral slip value
* Added accessors to set individual components of the driver input
Jorrit Rouwe 2 years ago
parent
commit
a1b946361d

+ 16 - 0
Jolt/Physics/Vehicle/TrackedVehicleController.h

@@ -90,6 +90,22 @@ public:
 	/// @param inBrake Value between 0 and 1 indicating how strong the brake pedal is pressed
 	void						SetDriverInput(float inForward, float inLeftRatio, float inRightRatio, float inBrake) { JPH_ASSERT(inLeftRatio != 0.0f && inRightRatio != 0.0f); mForwardInput = inForward; mLeftRatio = inLeftRatio; mRightRatio = inRightRatio; mBrakeInput = inBrake; }
 
+	/// Value between -1 and 1 for auto transmission and value between 0 and 1 indicating desired driving direction and amount the gas pedal is pressed
+	void						SetForwardInput(float inForward)			{ mForwardInput = inForward; }
+	float						GetForwardInput() const						{ return mForwardInput; }
+
+	/// Value between -1 and 1 indicating an extra multiplier to the rotation rate of the left track (used for steering)
+	void						SetLeftRatio(float inLeftRatio)				{ JPH_ASSERT(inLeftRatio != 0.0f); mLeftRatio = inLeftRatio; }
+	float						GetLeftRatio() const						{ return mLeftRatio; }
+
+	/// Value between -1 and 1 indicating an extra multiplier to the rotation rate of the right track (used for steering)
+	void						SetRightRatio(float inRightRatio)			{ JPH_ASSERT(inRightRatio != 0.0f); mRightRatio = inRightRatio; }
+	float						GetRightRatio() const						{ return mRightRatio; }
+
+	/// Value between 0 and 1 indicating how strong the brake pedal is pressed
+	void						SetBrakeInput(float inBrake)				{ mBrakeInput = inBrake; }
+	float						GetBrakeInput() const						{ return mBrakeInput; }
+
 	/// Get current engine state
 	const VehicleEngine &		GetEngine() const							{ return mEngine; }
 

+ 22 - 14
Jolt/Physics/Vehicle/VehicleConstraint.cpp

@@ -27,7 +27,7 @@ JPH_IMPLEMENT_SERIALIZABLE_VIRTUAL(VehicleConstraintSettings)
 }
 
 void VehicleConstraintSettings::SaveBinaryState(StreamOut &inStream) const
-{ 
+{
 	ConstraintSettings::SaveBinaryState(inStream);
 
 	inStream.Write(mUp);
@@ -158,6 +158,10 @@ void VehicleConstraint::OnStep(float inDeltaTime, PhysicsSystem &inPhysicsSystem
 {
 	JPH_PROFILE_FUNCTION();
 
+	// Callback to higher-level systems. We do it before PreCollide, in case steering changes.
+	if (mPreStepCallback != nullptr)
+		mPreStepCallback(*this, inDeltaTime, inPhysicsSystem);
+
 	// Calculate new world up vector by inverting gravity
 	mWorldUp = (-inPhysicsSystem.GetGravity()).NormalizedOr(mWorldUp);
 
@@ -219,6 +223,10 @@ void VehicleConstraint::OnStep(float inDeltaTime, PhysicsSystem &inPhysicsSystem
 		}
 	}
 
+	// Callback to higher-level systems. We do it immediately after wheel collision.
+	if (mPostCollideCallback != nullptr)
+		mPostCollideCallback(*this, inDeltaTime, inPhysicsSystem);
+
 	// Calculate anti-rollbar impulses
 	for (const VehicleAntiRollBar &r : mAntiRollBars)
 	{
@@ -260,7 +268,7 @@ void VehicleConstraint::OnStep(float inDeltaTime, PhysicsSystem &inPhysicsSystem
 		mBody->SetAllowSleeping(allow_sleep);
 }
 
-void VehicleConstraint::BuildIslands(uint32 inConstraintIndex, IslandBuilder &ioBuilder, BodyManager &inBodyManager) 
+void VehicleConstraint::BuildIslands(uint32 inConstraintIndex, IslandBuilder &ioBuilder, BodyManager &inBodyManager)
 {
 	// Find dynamic bodies that our wheels are touching
 	BodyID *body_ids = (BodyID *)JPH_STACK_ALLOC((mWheels.size() + 1) * sizeof(BodyID));
@@ -311,7 +319,7 @@ void VehicleConstraint::BuildIslands(uint32 inConstraintIndex, IslandBuilder &io
 	}
 
 	// Link the constraint in the island
-	ioBuilder.LinkConstraint(inConstraintIndex, mBody->GetIndexInActiveBodiesInternal(), min_active_index); 
+	ioBuilder.LinkConstraint(inConstraintIndex, mBody->GetIndexInActiveBodiesInternal(), min_active_index);
 }
 
 uint VehicleConstraint::BuildIslandSplits(LargeIslandSplitter &ioSplitter) const
@@ -399,7 +407,7 @@ void VehicleConstraint::SetupVelocityConstraint(float inDeltaTime)
 
 				// Calculate the damping and frequency of the suspension spring given the angle between the suspension direction and the contact normal
 				// If the angle between the suspension direction and the inverse of the contact normal is alpha then the force on the spring relates to the force along the contact normal as:
-				// 
+				//
 				// Fspring = Fnormal * cos(alpha)
 				//
 				// The spring force is:
@@ -413,15 +421,15 @@ void VehicleConstraint::SetupVelocityConstraint(float inDeltaTime)
 				// So we can see this as a spring with spring constant:
 				//
 				// k' = k / cos(alpha)
-				// 
+				//
 				// In the same way the velocity relates like:
-				// 
+				//
 				// Vspring = Vnormal * cos(alpha)
 				//
 				// Which results in the modified damping constant c:
 				//
 				// c' = c / cos(alpha)
-				// 
+				//
 				// Note that we clamp 1 / cos(alpha) to the range [0.1, 1] in order not to increase the stiffness / damping by too much.
 				Vec3 ws_direction = body_transform.Multiply3x3(settings->mSuspensionDirection);
 				float cos_angle = max(0.1f, ws_direction.Dot(neg_contact_normal));
@@ -441,7 +449,7 @@ void VehicleConstraint::SetupVelocityConstraint(float inDeltaTime)
 				w->mSuspensionMaxUpPart.CalculateConstraintProperties(*mBody, r1_plus_u, *w->mContactBody, r2, neg_contact_normal);
 			else
 				w->mSuspensionMaxUpPart.Deactivate();
-			
+
 			// Friction and propulsion
 			w->mLongitudinalPart.CalculateConstraintProperties(*mBody, r1_plus_u, *w->mContactBody, r2, -w->mContactLongitudinal);
 			w->mLateralPart.CalculateConstraintProperties(*mBody, r1_plus_u, *w->mContactBody, r2, -w->mContactLateral);
@@ -458,7 +466,7 @@ void VehicleConstraint::SetupVelocityConstraint(float inDeltaTime)
 	CalculatePitchRollConstraintProperties(body_transform);
 }
 
-void VehicleConstraint::WarmStartVelocityConstraint(float inWarmStartImpulseRatio) 
+void VehicleConstraint::WarmStartVelocityConstraint(float inWarmStartImpulseRatio)
 {
 	for (Wheel *w : mWheels)
 		if (w->mContactBody != nullptr)
@@ -468,13 +476,13 @@ void VehicleConstraint::WarmStartVelocityConstraint(float inWarmStartImpulseRati
 			w->mSuspensionPart.WarmStart(*mBody, *w->mContactBody, neg_contact_normal, inWarmStartImpulseRatio);
 			w->mSuspensionMaxUpPart.WarmStart(*mBody, *w->mContactBody, neg_contact_normal, inWarmStartImpulseRatio);
 			w->mLongitudinalPart.WarmStart(*mBody, *w->mContactBody, -w->mContactLongitudinal, 0.0f); // Don't warm start the longitudinal part (the engine/brake force, we don't want to preserve anything from the last frame)
-			w->mLateralPart.WarmStart(*mBody, *w->mContactBody, -w->mContactLateral, inWarmStartImpulseRatio);	
+			w->mLateralPart.WarmStart(*mBody, *w->mContactBody, -w->mContactLateral, inWarmStartImpulseRatio);
 		}
 
 	mPitchRollPart.WarmStart(*mBody, Body::sFixedToWorld, inWarmStartImpulseRatio);
 }
 
-bool VehicleConstraint::SolveVelocityConstraint(float inDeltaTime) 
+bool VehicleConstraint::SolveVelocityConstraint(float inDeltaTime)
 {
 	bool impulse = false;
 
@@ -503,7 +511,7 @@ bool VehicleConstraint::SolveVelocityConstraint(float inDeltaTime)
 	return impulse;
 }
 
-bool VehicleConstraint::SolvePositionConstraint(float inDeltaTime, float inBaumgarte) 
+bool VehicleConstraint::SolvePositionConstraint(float inDeltaTime, float inBaumgarte)
 {
 	bool impulse = false;
 
@@ -545,12 +553,12 @@ bool VehicleConstraint::SolvePositionConstraint(float inDeltaTime, float inBaumg
 
 #ifdef JPH_DEBUG_RENDERER
 
-void VehicleConstraint::DrawConstraint(DebugRenderer *inRenderer) const 
+void VehicleConstraint::DrawConstraint(DebugRenderer *inRenderer) const
 {
 	mController->Draw(inRenderer);
 }
 
-void VehicleConstraint::DrawConstraintLimits(DebugRenderer *inRenderer) const 
+void VehicleConstraint::DrawConstraintLimits(DebugRenderer *inRenderer) const
 {
 }
 

+ 27 - 11
Jolt/Physics/Vehicle/VehicleConstraint.h

@@ -17,7 +17,7 @@ JPH_NAMESPACE_BEGIN
 class PhysicsSystem;
 
 /// Configuration for constraint that simulates a wheeled vehicle.
-/// 
+///
 /// The properties in this constraint are largely based on "Car Physics for Games" by Marco Monster.
 /// See: https://www.asawicki.info/Mirror/Car%20Physics%20for%20Games/Car%20Physics%20for%20Games.html
 class JPH_EXPORT VehicleConstraintSettings : public ConstraintSettings
@@ -46,14 +46,14 @@ protected:
 /// When the vehicle drives over very light objects (rubble) you may see the car body dip down. This is a known issue and is an artifact of the iterative solver that Jolt is using.
 /// Basically if a light object is sandwiched between two heavy objects (the static floor and the car body), the light object is not able to transfer enough force from the ground to
 /// the car body to keep the car body up. You can see this effect in the HeavyOnLightTest sample, the boxes on the right have a lot of penetration because they're on top of light objects.
-/// 
+///
 /// There are a couple of ways to improve this:
-/// 
+///
 /// 1. You can increase the number of velocity steps (global settings PhysicsSettings::mNumVelocitySteps or if you only want to increase it on
 /// the vehicle you can use VehicleConstraintSettings::mNumVelocityStepsOverride). E.g. going from 10 to 30 steps in the HeavyOnLightTest sample makes the penetration a lot less.
 /// The number of position steps can also be increased (the first prevents the body from going down, the second corrects it if the problem did
 /// occur which inevitably happens due to numerical drift). This solution costs CPU cycles.
-/// 
+///
 /// 2. You can reduce the mass difference between the vehicle body and the rubble on the floor (by making the rubble heavier or the car lighter).
 ///
 /// 3. You could filter out collisions between the vehicle collision test and the rubble completely. This would make the wheels ignore the rubble but would cause the vehicle to drive
@@ -74,7 +74,7 @@ public:
 
 	/// Defines the maximum pitch/roll angle (rad), can be used to avoid the car from getting upside down. The vehicle up direction will stay within a cone centered around the up axis with half top angle mMaxPitchRollAngle, set to pi to turn off.
 	void						SetMaxPitchRollAngle(float inMaxPitchRollAngle) { mCosMaxPitchRollAngle = Cos(inMaxPitchRollAngle); }
-	
+
 	/// Set the interface that tests collision between wheel and ground
 	void						SetVehicleCollisionTester(const VehicleCollisionTester *inTester) { mVehicleCollisionTester = inTester; }
 
@@ -86,14 +86,26 @@ public:
 	void						SetCombineFriction(CombineFunction inCombineFriction) { mCombineFriction = inCombineFriction; }
 	CombineFunction				GetCombineFriction() const					{ return mCombineFriction; }
 
-	/// Callback function to notify that PhysicsStepListener::OnStep has completed for this vehicle.
-	using PostStepCallback = function<void(VehicleConstraint &inVehicle, float inDeltaTime, PhysicsSystem &inPhysicsSystem)>;
+	/// Callback function to notify of current stage in PhysicsStepListener::OnStep.
+	using StepCallback = function<void(VehicleConstraint &inVehicle, float inDeltaTime, PhysicsSystem &inPhysicsSystem)>;
+
+	/// Callback function to notify that PhysicsStepListener::OnStep has started for this vehicle. Default is to do nothing.
+	/// Can be used to allow higher-level code to e.g. control steering. This is the last moment that the position/orientation of the vehicle can be changed.
+	/// Wheel collision checks have not been performed yet.
+	const StepCallback &		GetPreStepCallback() const					{ return mPreStepCallback; }
+	void						SetPreStepCallback(const StepCallback &inPreStepCallback) { mPreStepCallback = inPreStepCallback; }
+
+	/// Callback function to notify that PhysicsStepListener::OnStep has just completed wheel collision checks. Default is to do nothing.
+	/// Can be used to allow higher-level code to e.g. detect tire contact or to modify the velocity of the vehicle based on the wheel contacts.
+	/// You should not change the position of the vehicle in this callback as the wheel collision checks have already been performed.
+	const StepCallback &		GetPostCollideCallback() const				{ return mPostCollideCallback; }
+	void						SetPostCollideCallback(const StepCallback &inPostCollideCallback) { mPostCollideCallback = inPostCollideCallback; }
 
 	/// Callback function to notify that PhysicsStepListener::OnStep has completed for this vehicle. Default is to do nothing.
-	/// Can be used to adjust the velocity of the vehicle to allow higher-level code to e.g. control the vehicle in the air.
+	/// Can be used to allow higher-level code to e.g. control the vehicle in the air.
 	/// You should not change the position of the vehicle in this callback as the wheel collision checks have already been performed.
-	const PostStepCallback &	GetPostStepCallback() const					{ return mPostStepCallback; }
-	void						SetPostStepCallback(const PostStepCallback &inPostStepCallback) { mPostStepCallback = inPostStepCallback; }
+	const StepCallback &		GetPostStepCallback() const					{ return mPostStepCallback; }
+	void						SetPostStepCallback(const StepCallback &inPostStepCallback) { mPostStepCallback = inPostStepCallback; }
 
 	/// Get the local space forward vector of the vehicle
 	Vec3						GetLocalForward() const						{ return mForward; }
@@ -188,7 +200,11 @@ private:
 	// Interfaces
 	RefConst<VehicleCollisionTester> mVehicleCollisionTester;				///< Class that performs testing of collision for the wheels
 	CombineFunction				mCombineFriction = [](float inTireFriction, const Body &inBody2, const SubShapeID &) { return sqrt(inTireFriction * inBody2.GetFriction()); };
-	PostStepCallback			mPostStepCallback;
+
+	// Callbacks
+	StepCallback				mPreStepCallback;
+	StepCallback				mPostCollideCallback;
+	StepCallback				mPostStepCallback;
 };
 
 JPH_NAMESPACE_END

+ 16 - 14
Jolt/Physics/Vehicle/WheeledVehicleController.cpp

@@ -32,7 +32,7 @@ JPH_IMPLEMENT_SERIALIZABLE_VIRTUAL(WheeledVehicleControllerSettings)
 JPH_IMPLEMENT_SERIALIZABLE_VIRTUAL(WheelSettingsWV)
 {
 	JPH_ADD_ATTRIBUTE(WheelSettingsWV, mInertia)
-	JPH_ADD_ATTRIBUTE(WheelSettingsWV, mAngularDamping)	
+	JPH_ADD_ATTRIBUTE(WheelSettingsWV, mAngularDamping)
 	JPH_ADD_ATTRIBUTE(WheelSettingsWV, mMaxSteerAngle)
 	JPH_ADD_ATTRIBUTE(WheelSettingsWV, mLongitudinalFriction)
 	JPH_ADD_ATTRIBUTE(WheelSettingsWV, mLateralFriction)
@@ -116,7 +116,8 @@ void WheelWV::Update(float inDeltaTime, const VehicleConstraint &inConstraint)
 
 		// Calculate lateral friction based on slip angle
 		float relative_velocity_len = relative_velocity.Length();
-		float lateral_slip_angle = relative_velocity_len < 1.0e-3f? 0.0f : RadiansToDegrees(ACos(abs(relative_longitudinal_velocity) / relative_velocity_len));
+		mLateralSlip = relative_velocity_len < 1.0e-3f ? 0.0f : ACos(abs(relative_longitudinal_velocity) / relative_velocity_len);
+		float lateral_slip_angle = RadiansToDegrees(mLateralSlip);
 		float lateral_slip_friction = settings->mLateralFriction.GetValue(lateral_slip_angle);
 
 		// Tire friction
@@ -128,6 +129,7 @@ void WheelWV::Update(float inDeltaTime, const VehicleConstraint &inConstraint)
 	{
 		// No collision
 		mLongitudinalSlip = 0.0f;
+		mLateralSlip = 0.0f;
 		mCombinedLongitudinalFriction = mCombinedLateralFriction = 0.0f;
 	}
 }
@@ -138,7 +140,7 @@ VehicleController *WheeledVehicleControllerSettings::ConstructController(Vehicle
 }
 
 void WheeledVehicleControllerSettings::SaveBinaryState(StreamOut &inStream) const
-{ 
+{
 	mEngine.SaveBinaryState(inStream);
 
 	mTransmission.SaveBinaryState(inStream);
@@ -402,7 +404,7 @@ void WheeledVehicleController::PostCollide(float inDeltaTime, PhysicsSystem &inP
 	if (!driven_wheels.empty())
 	{
 		// Define the torque at the clutch at time t as:
-		// 
+		//
 		// tc(t):=S*(we(t)-sum(R(j)*ww(j,t),j,1,N)/N)
 		//
 		// Where:
@@ -413,7 +415,7 @@ void WheeledVehicleController::PostCollide(float inDeltaTime, PhysicsSystem &inP
 		// N is the amount of wheels
 		//
 		// The torque that increases the engine angular velocity at time t is:
-		// 
+		//
 		// te(t):=TE-tc(t)
 		//
 		// Where:
@@ -454,7 +456,7 @@ void WheeledVehicleController::PostCollide(float inDeltaTime, PhysicsSystem &inP
 		// Expanding both equations (the equations above are in wxMaxima format and this can easily be done by expand(%)):
 		//
 		// For wheel:
-		// 
+		//
 		// 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)
 		//
 		// For engine:
@@ -479,7 +481,7 @@ void WheeledVehicleController::PostCollide(float inDeltaTime, PhysicsSystem &inP
 
 		// Get number of driven wheels as a float
 		float num_driven_wheels_float = float(driven_wheels.size());
-	
+
 		// Angular velocity of engine
 		float w_engine = mEngine.GetAngularVelocity();
 
@@ -608,7 +610,7 @@ void WheeledVehicleController::PostCollide(float inDeltaTime, PhysicsSystem &inP
 
 	// Update transmission
 	mTransmission.Update(inDeltaTime, mEngine.GetCurrentRPM(), mForwardInput, can_shift_up);
-	
+
 	// Braking
 	for (Wheel *w_base : wheels)
 	{
@@ -645,7 +647,7 @@ void WheeledVehicleController::PostCollide(float inDeltaTime, PhysicsSystem &inP
 	mPreviousDeltaTime = inDeltaTime;
 }
 
-bool WheeledVehicleController::SolveLongitudinalAndLateralConstraints(float inDeltaTime) 
+bool WheeledVehicleController::SolveLongitudinalAndLateralConstraints(float inDeltaTime)
 {
 	bool impulse = false;
 
@@ -717,7 +719,7 @@ bool WheeledVehicleController::SolveLongitudinalAndLateralConstraints(float inDe
 
 #ifdef JPH_DEBUG_RENDERER
 
-void WheeledVehicleController::Draw(DebugRenderer *inRenderer) const 
+void WheeledVehicleController::Draw(DebugRenderer *inRenderer) const
 {
 	float constraint_size = mConstraint.GetDrawConstraintSize();
 
@@ -732,15 +734,15 @@ void WheeledVehicleController::Draw(DebugRenderer *inRenderer) const
 	{
 		// Calculate average wheel speed at clutch
 		float wheel_speed_at_clutch = GetWheelSpeedAtClutch();
-		
+
 		// Draw the average wheel speed measured at clutch to compare engine RPM with wheel RPM
 		inRenderer->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);
 	}
 
 	// Draw current vehicle state
 	String status = StringFormat("Forward: %.1f, Right: %.1f\nBrake: %.1f, HandBrake: %.1f\n"
-								 "Gear: %d, Clutch: %.1f\nEngineRPM: %.0f, V: %.1f km/h", 
-								 (double)mForwardInput, (double)mRightInput, (double)mBrakeInput, (double)mHandBrakeInput, 
+								 "Gear: %d, Clutch: %.1f\nEngineRPM: %.0f, V: %.1f km/h",
+								 (double)mForwardInput, (double)mRightInput, (double)mBrakeInput, (double)mHandBrakeInput,
 								 mTransmission.GetCurrentGear(), (double)mTransmission.GetClutchFriction(), (double)mEngine.GetCurrentRPM(), (double)body->GetLinearVelocity().Length() * 3.6);
 	inRenderer->DrawText3D(body->GetPosition(), status, Color::sWhite, constraint_size);
 
@@ -784,7 +786,7 @@ void WheeledVehicleController::Draw(DebugRenderer *inRenderer) const
 			inRenderer->DrawLine(w->GetContactPosition(), w->GetContactPosition() + w->GetContactLongitudinal(), Color::sRed);
 			inRenderer->DrawLine(w->GetContactPosition(), w->GetContactPosition() + w->GetContactLateral(), Color::sBlue);
 
-			DebugRenderer::sInstance->DrawText3D(wheel_pos, StringFormat("W: %.1f, S: %.2f\nSlip: %.2f, FrLateral: %.1f, FrLong: %.1f", (double)w->GetAngularVelocity(), (double)w->GetSuspensionLength(), (double)w->mLongitudinalSlip, (double)w->mCombinedLateralFriction, (double)w->mCombinedLongitudinalFriction), Color::sWhite, constraint_size);
+			DebugRenderer::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);
 		}
 		else
 		{

+ 18 - 1
Jolt/Physics/Vehicle/WheeledVehicleController.h

@@ -59,13 +59,14 @@ public:
 	void						Update(float inDeltaTime, const VehicleConstraint &inConstraint);
 
 	float						mLongitudinalSlip = 0.0f;					///< Velocity difference between ground and wheel relative to ground velocity
+	float						mLateralSlip = 0.0f;						///< Angular difference (in radians) between ground and wheel relative to ground velocity
 	float						mCombinedLongitudinalFriction = 0.0f;		///< Combined friction coefficient in longitudinal direction (combines terrain and tires)
 	float						mCombinedLateralFriction = 0.0f;			///< Combined friction coefficient in lateral direction (combines terrain and tires)
 	float						mBrakeImpulse = 0.0f;						///< Amount of impulse that the brakes can apply to the floor (excluding friction)
 };
 
 /// Settings of a vehicle with regular wheels
-/// 
+///
 /// The properties in this controller are largely based on "Car Physics for Games" by Marco Monster.
 /// See: https://www.asawicki.info/Mirror/Car%20Physics%20for%20Games/Car%20Physics%20for%20Games.html
 class JPH_EXPORT WheeledVehicleControllerSettings : public VehicleControllerSettings
@@ -103,6 +104,22 @@ public:
 	/// @param inHandBrake Value between 0 and 1 indicating how strong the hand brake is pulled
 	void						SetDriverInput(float inForward, float inRight, float inBrake, float inHandBrake) { mForwardInput = inForward; mRightInput = inRight; mBrakeInput = inBrake; mHandBrakeInput = inHandBrake; }
 
+	/// Value between -1 and 1 for auto transmission and value between 0 and 1 indicating desired driving direction and amount the gas pedal is pressed
+	void						SetForwardInput(float inForward)			{ mForwardInput = inForward; }
+	float						GetForwardInput() const						{ return mForwardInput; }
+
+	/// Value between -1 and 1 indicating desired steering angle (1 = right)
+	void						SetRightInput(float inRight)				{ mRightInput = inRight; }
+	float						GetRightInput() const						{ return mRightInput; }
+
+	/// Value between 0 and 1 indicating how strong the brake pedal is pressed
+	void						SetBrakeInput(float inBrake)				{ mBrakeInput = inBrake; }
+	float						GetBrakeInput() const						{ return mBrakeInput; }
+
+	/// Value between 0 and 1 indicating how strong the hand brake is pulled
+	void						SetHandBrakeInput(float inHandBrake)		{ mHandBrakeInput = inHandBrake; }
+	float						GetHandBrakeInput() const					{ return mHandBrakeInput; }
+
 	/// Get current engine state
 	const VehicleEngine &		GetEngine() const							{ return mEngine; }