Skip to content

Commit

Permalink
feat: Add AutoDrive
Browse files Browse the repository at this point in the history
  • Loading branch information
Vatsal Ambastha committed Apr 26, 2020
1 parent baff332 commit 22bb006
Show file tree
Hide file tree
Showing 10 changed files with 255 additions and 25 deletions.
51 changes: 51 additions & 0 deletions Assets/Tork/Runtime/Addons/AutoDrive.cs
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
using UnityEngine;

namespace Adrenak.Tork {
public class AutoDrive : VehicleAddOn {
public Vehicle vehicle;
public Transform destination;
public float rate = .5f;
public float minDistance;
public AnimationCurve accelerationVsDist = AnimationCurve.Linear(0, .5f, 50, 1f);

public bool IsInReverseArea {
get {
var towards = destination.position - transform.position;
var locTowards = transform.InverseTransformDirection(towards);

var currMaxSteerAngle = Mathf.Abs(vehicle.Steering.range);
var separation = vehicle.Ackermann.AxleSeparation;
var width = vehicle.Ackermann.AxleWidth;
var currMinRadius = Ackermann.GetRadius(currMaxSteerAngle, separation, width);
var pivot = vehicle.transform.position + vehicle.transform.right * Mathf.Sign(locTowards.x) * currMinRadius;

if (Vector3.Distance(pivot, destination.position) < currMinRadius)
return true;

bool isBehind = locTowards.z < 0;
if (isBehind && Vector3.Distance(pivot, destination.position) < currMinRadius * 2)
return true;

return false;
}
}

void Update() {
var distance = Vector3.Distance(vehicle.transform.position, destination.position);

var towards = destination.position - transform.position;
var locTowards = transform.InverseTransformDirection(towards);
var reqAngle = Vector3.Angle(transform.forward, towards) * Mathf.Sign(locTowards.x);

var isAhead = locTowards.z > 0;

if (isAhead)
vehicle.Brake.value = 1 - (distance / minDistance);
else
vehicle.Brake.value = 0;

vehicle.Motor.value = accelerationVsDist.Evaluate(distance) * (IsInReverseArea ? -1 : 1);
vehicle.Steering.Angle = Mathf.Lerp(vehicle.Steering.Angle, reqAngle, rate) * (IsInReverseArea ? -1 : 1);
}
}
}
11 changes: 11 additions & 0 deletions Assets/Tork/Runtime/Addons/AutoDrive.cs.meta

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

5 changes: 5 additions & 0 deletions Assets/Tork/Runtime/Core/Ackermann.cs
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,11 @@ public static float GetSecondaryAngle(float angle, float width, float separation
return Mathf.Atan(separation / far) * Mathf.Rad2Deg;
}

public static float GetRadius(float angle, float separation, float width){
var radii = GetRadii(angle, separation, width);
return radii[0, 0] + radii[0, 1] + radii[1, 0] + radii[1, 1] / 4;
}

public static float[,] GetRadii(float angle, float separation, float width) {
var secAngle = GetSecondaryAngle(angle, width, separation);
float[,] radii = new float[2, 2];
Expand Down
2 changes: 2 additions & 0 deletions Assets/Tork/Runtime/Core/Brakes.cs
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@ public class Brakes : MonoBehaviour {
public float value;

void FixedUpdate() {
value = Mathf.Clamp01(value);

float fr, fl, rr, rl;

// If we have Ackerman steering, we apply torque based on the steering radius of each wheel
Expand Down
31 changes: 19 additions & 12 deletions Assets/Tork/Runtime/Core/Steering.cs
Original file line number Diff line number Diff line change
@@ -1,19 +1,26 @@
using UnityEngine;

namespace Adrenak.Tork {
public class Steering : MonoBehaviour {
public float range = 35;
public float value; // 0..1
public float rate = 45;
public class Steering : MonoBehaviour {
public float range = 35;
public float value; // 0..1
public float rate = 45;

public Ackermann ackermann;
float m_CurrAngle;
float m_CurrAngle;

void Update() {
var destination = value * range;
m_CurrAngle = Mathf.MoveTowards(m_CurrAngle, destination, Time.deltaTime * rate);
m_CurrAngle = Mathf.Clamp(m_CurrAngle, -range, range);
ackermann.SetAngle(m_CurrAngle);
}
}
public float Angle {
get { return range * value; }
set {
this.value = value / range;
}
}

void Update() {
var destination = value * range;
m_CurrAngle = Mathf.MoveTowards(m_CurrAngle, destination, Time.deltaTime * rate);
m_CurrAngle = Mathf.Clamp(m_CurrAngle, -range, range);
ackermann.SetAngle(m_CurrAngle);
}
}
}
2 changes: 1 addition & 1 deletion Assets/Tork/Runtime/Core/TorkWheel.cs
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ void CalculateFriction() {
// Apply brake resistance force
var brakeResistanceForceMag = BrakeTorque / radius;
brakeResistanceForceMag = Mathf.Clamp(brakeResistanceForceMag, 0, longForce.magnitude);
Vector3 brakeResistanceForce = longForce.normalized * brakeResistanceForceMag;
Vector3 brakeResistanceForce = longForce.normalized * brakeResistanceForceMag * engineShaftToWheelRatio;
longForce -= brakeResistanceForce;

gripResistanceForce -= longForce;
Expand Down
8 changes: 8 additions & 0 deletions Assets/Tork/Runtime/Utils.meta

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

7 changes: 2 additions & 5 deletions Assets/Tork/Samples/Scenes/Demo.cs
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,13 @@
namespace Adrenak.Tork.Demo {
public class Demo : MonoBehaviour {
[Header("Common")]
public Vehicle vehiclePrefab;
public Transform spawnPoint;
public Vehicle vehicle;
public SmoothFollow smoothFollow;

IVehicleDriver driver;
Vehicle vehicle;
MidAirStabilization midAirStabilization;

void Start() {
vehicle = Instantiate(vehiclePrefab, spawnPoint.position, spawnPoint.rotation);
midAirStabilization = vehicle.GetAddOn<MidAirStabilization>();

driver = new KeyboardVehicleDriver();
Expand All @@ -22,7 +19,7 @@ void Start() {
}

void Update() {
driver.DriveVehicles();
//driver.DriveVehicles();

if (Input.GetKeyDown(KeyCode.R))
midAirStabilization.enabled = !midAirStabilization.enabled;
Expand Down
157 changes: 153 additions & 4 deletions Assets/Tork/Samples/Scenes/Demo.unity
Original file line number Diff line number Diff line change
Expand Up @@ -387,6 +387,77 @@ MeshFilter:
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 194512612}
m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0}
--- !u!1 &255152389
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 255152390}
- component: {fileID: 255152392}
m_Layer: 0
m_Name: Auto Drive
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &255152390
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 255152389}
m_LocalRotation: {x: 0, y: 0, z: 0, w: 1}
m_LocalPosition: {x: 0, y: 0, z: 0}
m_LocalScale: {x: 1, y: 1, z: 1}
m_Children: []
m_Father: {fileID: 1553216374}
m_RootOrder: 7
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &255152392
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 255152389}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: 04ba35be00207f1408fcd9d4f9881aaf, type: 3}
m_Name:
m_EditorClassIdentifier:
vehicle: {fileID: 1151711987}
destination: {fileID: 595338423}
rate: 0.5
minDistance: 5
accelerationVsDist:
serializedVersion: 2
m_Curve:
- serializedVersion: 3
time: 0
value: 0.5
inSlope: 0
outSlope: 0.01
tangentMode: 0
weightedMode: 0
inWeight: 0
outWeight: 0
- serializedVersion: 3
time: 50
value: 1
inSlope: 0.01
outSlope: 0
tangentMode: 0
weightedMode: 0
inWeight: 0
outWeight: 0
m_PreInfinity: 2
m_PostInfinity: 2
m_RotationOrder: 4
--- !u!1 &282068337
GameObject:
m_ObjectHideFlags: 0
Expand Down Expand Up @@ -1176,7 +1247,7 @@ SphereCollider:
m_GameObject: {fileID: 595338419}
m_Material: {fileID: 0}
m_IsTrigger: 0
m_Enabled: 1
m_Enabled: 0
serializedVersion: 2
m_Radius: 0.5
m_Center: {x: 0, y: 0, z: 0}
Expand Down Expand Up @@ -2589,6 +2660,18 @@ Transform:
m_Father: {fileID: 1193580804}
m_RootOrder: 0
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &1151711987 stripped
MonoBehaviour:
m_CorrespondingSourceObject: {fileID: 114480416164222720, guid: 58b5a3e507c7b68449674674e18cab44,
type: 3}
m_PrefabInstance: {fileID: 2072883566}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 0}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: 1da1bb9a22dc0004c803629affe1f6df, type: 3}
m_Name:
m_EditorClassIdentifier:
--- !u!1 &1193580803
GameObject:
m_ObjectHideFlags: 0
Expand Down Expand Up @@ -3209,6 +3292,12 @@ MeshFilter:
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 1506344195}
m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0}
--- !u!4 &1553216374 stripped
Transform:
m_CorrespondingSourceObject: {fileID: 2425653309673728414, guid: 58b5a3e507c7b68449674674e18cab44,
type: 3}
m_PrefabInstance: {fileID: 2072883566}
m_PrefabAsset: {fileID: 0}
--- !u!1 &1602958346
GameObject:
m_ObjectHideFlags: 0
Expand Down Expand Up @@ -3994,9 +4083,7 @@ MonoBehaviour:
m_Script: {fileID: 11500000, guid: 32a07620c0661354ab24415957a77749, type: 3}
m_Name:
m_EditorClassIdentifier:
vehiclePrefab: {fileID: 114480416164222720, guid: 58b5a3e507c7b68449674674e18cab44,
type: 3}
spawnPoint: {fileID: 358142904}
vehicle: {fileID: 1151711987}
smoothFollow: {fileID: 1853051912}
--- !u!4 &2016063157
Transform:
Expand All @@ -4012,6 +4099,68 @@ Transform:
m_Father: {fileID: 0}
m_RootOrder: 3
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!1001 &2072883566
PrefabInstance:
m_ObjectHideFlags: 0
serializedVersion: 2
m_Modification:
m_TransformParent: {fileID: 0}
m_Modifications:
- target: {fileID: 1132797446414550, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_Name
value: Tocus
objectReference: {fileID: 0}
- target: {fileID: 1214198106157320312, guid: 58b5a3e507c7b68449674674e18cab44,
type: 3}
propertyPath: maxTorque
value: 1000
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalPosition.x
value: 18.88
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalPosition.y
value: 1.5
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalPosition.z
value: 44.7
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalRotation.x
value: 0
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalRotation.y
value: 0
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalRotation.z
value: 0
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalRotation.w
value: 1
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_RootOrder
value: 6
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalEulerAnglesHint.x
value: 0
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalEulerAnglesHint.y
value: 0
objectReference: {fileID: 0}
- target: {fileID: 4261489924384528, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
propertyPath: m_LocalEulerAnglesHint.z
value: 0
objectReference: {fileID: 0}
m_RemovedComponents: []
m_SourcePrefab: {fileID: 100100000, guid: 58b5a3e507c7b68449674674e18cab44, type: 3}
--- !u!1 &2079960472
GameObject:
m_ObjectHideFlags: 0
Expand Down
6 changes: 3 additions & 3 deletions ProjectSettings/EditorBuildSettings.asset
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ EditorBuildSettings:
m_ObjectHideFlags: 0
serializedVersion: 2
m_Scenes:
- enabled: 1
path: Assets/Tork/Samples/Demo-AIDriver/AIDemo.unity
guid: 34a95e22abc6dd345b998f1a7cddd0cb
- enabled: 0
path:
guid: 00000000000000000000000000000000
m_configObjects: {}

0 comments on commit 22bb006

Please sign in to comment.