Skip to content

Commit 4f9bbbb

Browse files
authored
fix: camera position on reset (#171)
Signed-off-by: Alptuğ Cırıt <[email protected]>
1 parent b7bf152 commit 4f9bbbb

File tree

6 files changed

+68
-43
lines changed

6 files changed

+68
-43
lines changed

Assets/AWSIM/Prefabs/Vehicles/Lexus RX450h 2015 Sample Sensor.prefab

+17-18
Original file line numberDiff line numberDiff line change
@@ -1220,21 +1220,16 @@ MonoBehaviour:
12201220
m_Script: {fileID: -1898320663, guid: b8873f7cd5fec6f49a4b37228b9b23ac, type: 3}
12211221
m_Name:
12221222
m_EditorClassIdentifier:
1223-
integrationSteps: 8
1224-
integrationUseRK4: 0
12251223
centerOfMass: {fileID: 2963107001226707149}
1226-
tireSideDeflection: 0
1227-
tireSideDeflectionRate: 10
1228-
tireAdherentImpulseRatio: 0.5
1229-
wheelSleepVelocity: 0.2
1230-
advancedSuspensionDamper: 1
1231-
suspensionDamperLimitFactor: 2
1224+
solverSubsteps: 8
1225+
wheelMomentumFactor: 0.25
1226+
wheelMomentumModel: 0
12321227
contactAngleAffectsTireForce: 1
12331228
dontAdjustSuspensionForcePoint: 0
12341229
disableSteerAngleFix: 0
12351230
disableWheelReferenceFrameFix: 0
12361231
scaleFactor: 1
1237-
vehicleSleepCriteria: 0
1232+
suspensionDamperLimitFactor: 2
12381233
showContactGizmos: 1
12391234
disableContactProcessing: 0
12401235
inertia:
@@ -1333,6 +1328,7 @@ MonoBehaviour:
13331328
ackerman: 1
13341329
ackermanReference: {fileID: 5055317025945945549}
13351330
ratioReference: {fileID: 0}
1331+
steeringWheelRange: 900
13361332
brakes:
13371333
maxBrakeTorque: 2800
13381334
brakeBias: 0.68
@@ -1357,7 +1353,6 @@ MonoBehaviour:
13571353
E: -2
13581354
adherent: {x: 0.5, y: -1}
13591355
frictionMultiplier: 1
1360-
maxAdherentSpeed: 6.388889
13611356
engine:
13621357
idleRpm: 1000
13631358
peakRpm: 7700
@@ -1423,12 +1418,14 @@ MonoBehaviour:
14231418
automaticShiftInterval: 1
14241419
automaticGearDownRevs: 2000
14251420
automaticGearUpRevs: 5000
1421+
automaticMaxRpm: 5500
14261422
automaticThrottleSens: 0
14271423
automaticThrottleSensMin: 0.6
14281424
automaticFullThrottleGearDownRevs: 3000
14291425
automaticFullThrottleGearUpRevs: 4500
1430-
automaticGearUpRequiresThrottle: 1
14311426
automaticShiftReverseGears: 0
1427+
automaticGearUpRequiresThrottle: 1
1428+
automaticGearUpAboveMaxRpm: 0
14321429
automaticInitialGearForward: 1
14331430
automaticInitialGearReverse: -1
14341431
antiLock:
@@ -1460,11 +1457,11 @@ MonoBehaviour:
14601457
maxSpeed: 5.555556
14611458
minRotationDiffRpm: 100
14621459
maxRotationDiffRpm: 400
1463-
maxBrakeTorque: 1000
1460+
maxBrakeRatio: 1
14641461
engineReactionFactor: 1
14651462
parkModeReactionFactor: 0.95
14661463
maxSubsystemsEnergy: 100000
1467-
"\u202A\u206C\u202D\u206D\u200B\u206E\u202B\u202B\u202D\u206D\u206B\u200E\u206B\u202C\u206B\u202C\u202B\u206F\u202C\u200F\u202B\u202C\u202C\u200B\u206C\u206E\u202A\u202B\u200B\u200B\u200F\u200D\u206F\u202C\u200C\u206F\u202D\u206E\u206D\u206A\u202E": 1
1464+
"\u200B\u202A\u202B\u200F\u200B\u206F\u206D\u202E\u206D\u202D\u206E\u206E\u206C\u206F\u202B\u200E\u202D\u206E\u206C\u202B\u202D\u200F\u202D\u202D\u200D\u200B\u202D\u206A\u202D\u202B\u200D\u202E\u202E\u202A\u202E\u202A\u206A\u206F\u206A\u206E\u202E": 1
14681465
--- !u!114 &3608516095911096369
14691466
MonoBehaviour:
14701467
m_ObjectHideFlags: 0
@@ -1497,7 +1494,9 @@ MonoBehaviour:
14971494
disableSteerInput: 0
14981495
disableThrottleInput: 0
14991496
disableBrakeInput: 0
1497+
disableHandbrakeInput: 0
15001498
disableClutchInput: 0
1499+
disableGearShiftInputs: 0
15011500
externalThrottle: 0
15021501
reverse: 0
15031502
externalBrake: 0
@@ -1557,7 +1556,6 @@ MonoBehaviour:
15571556
showContactPoints: 1
15581557
showTireSlip: 1
15591558
showTireForces: 1
1560-
showSurfaceForces: 0
15611559
useLogScale: 1
15621560
--- !u!114 &8627087200372202738
15631561
MonoBehaviour:
@@ -1572,7 +1570,6 @@ MonoBehaviour:
15721570
m_Name:
15731571
m_EditorClassIdentifier:
15741572
steeringWheel: {fileID: 0}
1575-
degreesOfRotation: 600
15761573
localRotationAxis: 2
15771574
brakeLightsOn:
15781575
- {fileID: 0}
@@ -1619,7 +1616,7 @@ MonoBehaviour:
16191616
_simulateSteering: 0
16201617
_steerWheelInput: 45
16211618
_emergencyBrakePercent: 100
1622-
_updatePositionOffsetY: 1.33
1619+
_updatePositionOffsetY: 0.5
16231620
_updatePositionRayOriginY: 1000
16241621
_doPedalCalibration: 0
16251622
--- !u!114 &8380214914162268112
@@ -3412,13 +3409,15 @@ MonoBehaviour:
34123409
m_Name:
34133410
m_EditorClassIdentifier:
34143411
dynamicModel: 0
3415-
dynamicCoefficient: 0.04
3412+
constantCoefficient: 0.04
3413+
linearCoefficient: 0.0003
3414+
tirePressure: 2
34163415
staticCoefficient: 0.004
34173416
staticSpeedThreshold: 2
34183417
axleFrictionFactors: []
34193418
showDebugLabel: 0
34203419
coefficient: -1
3421-
version: 1
3420+
version: 2
34223421
--- !u!114 &7226978134186799435
34233422
MonoBehaviour:
34243423
m_ObjectHideFlags: 0

Assets/AWSIM/Scripts/UI/EgoVehiclePositionManager.cs

+10-7
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,16 @@
1+
using System;
12
using UnityEngine;
2-
using VehiclePhysics;
33

44
namespace AWSIM.Scripts.UI
55
{
66
public class EgoVehiclePositionManager : MonoBehaviour
77
{
88
public Transform EgoTransform { private get; set; }
9-
private Vector3 initialEgoPosition;
10-
private Quaternion initialEgoRotation;
9+
private Vector3 _initialEgoPosition;
10+
private Quaternion _initialEgoRotation;
11+
12+
// Event to notify subscribers that the ego vehicle has been reset to the spawn point.
13+
public event Action<Vector3, Quaternion> OnEgoReset;
1114

1215
private void Start()
1316
{
@@ -23,8 +26,8 @@ public void Activate()
2326
private void InitializeEgoTransform(Transform egoTransform)
2427
{
2528
EgoTransform = egoTransform;
26-
initialEgoPosition = EgoTransform.position;
27-
initialEgoRotation = EgoTransform.rotation;
29+
_initialEgoPosition = EgoTransform.position;
30+
_initialEgoRotation = EgoTransform.rotation;
2831
}
2932

3033
// If the ego transform reference is present, reset the ego to the initial position and rotation.
@@ -36,8 +39,8 @@ public void ResetEgoToSpawnPoint()
3639
return;
3740
}
3841

39-
var vpController = EgoTransform.GetComponent<VPVehicleController>();
40-
vpController.HardReposition(initialEgoPosition, initialEgoRotation);
42+
// Reset the ego vehicle to the initial position and rotation.
43+
OnEgoReset?.Invoke(_initialEgoPosition, _initialEgoRotation);
4144
}
4245
}
4346
}

Assets/AWSIM/Scripts/UI/VehicleDashboard.cs

+9-15
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@ namespace AWSIM.Scripts.UI
1515
public class VehicleDashboard : MonoBehaviour
1616
{
1717
private VPVehicleController _vehicleController;
18-
private int[] _vehicleDataBus;
1918
private AutowareVPPAdapter _adapter;
2019
[Header("Speed")]
2120
[SerializeField] private Text _speedText;
@@ -39,26 +38,21 @@ public class VehicleDashboard : MonoBehaviour
3938

4039
private const float MsToKmH = 3.6f;
4140

42-
private void Start()
41+
private void GetVariables()
4342
{
4443
_vehicleController = FindObjectOfType<VPVehicleController>();
45-
_vehicleDataBus = _vehicleController.data.bus[Channel.Vehicle];
4644
_adapter = FindObjectOfType<AutowareVPPAdapter>();
47-
48-
if (_vehicleController == null || _adapter == null)
49-
{
50-
Debug.LogError("VehicleController or AutowareVPPAdapter component not found!");
51-
}
5245
}
5346

5447
public void Activate()
5548
{
56-
Start();
49+
GetVariables();
5750
}
5851

5952
private void FixedUpdate()
6053
{
6154
if (_vehicleController == null) return;
55+
if (_adapter == null) return;
6256

6357
UpdateDashboard();
6458
}
@@ -67,12 +61,12 @@ private void UpdateDashboard()
6761
{
6862
_speedText.text = UpdateSpeed(_vehicleController);
6963
// _transmissionModeText.text = UpdateTransmissionMode(_vehicleDataBus[VehicleData.GearboxMode]);
70-
_gearText.text = UpdateGear(_vehicleDataBus[VehicleData.GearboxGear]);
64+
_gearText.text = UpdateGear(_vehicleController.data.bus[Channel.Vehicle][VehicleData.GearboxGear]);
7165

72-
UpdateSystemState(_vehicleDataBus[VehicleData.AbsEngaged], _absText);
73-
UpdateSystemState(_vehicleDataBus[VehicleData.AsrEngaged], _asrText);
74-
UpdateSystemState(_vehicleDataBus[VehicleData.EscEngaged], _escText);
75-
UpdateSystemState(_vehicleDataBus[VehicleData.TcsEngaged], _tcsText);
66+
UpdateSystemState(_vehicleController.data.bus[Channel.Vehicle][VehicleData.AbsEngaged], _absText);
67+
UpdateSystemState(_vehicleController.data.bus[Channel.Vehicle][VehicleData.AsrEngaged], _asrText);
68+
UpdateSystemState(_vehicleController.data.bus[Channel.Vehicle][VehicleData.EscEngaged], _escText);
69+
UpdateSystemState(_vehicleController.data.bus[Channel.Vehicle][VehicleData.TcsEngaged], _tcsText);
7670

7771
// UpdateControlMode();
7872
UpdateControlModeImage();
@@ -166,7 +160,7 @@ private string UpdateGear(int gearVal)
166160
return gearVal switch
167161
{
168162
< 0 => "R",
169-
0 => _vehicleDataBus[VehicleData.GearboxMode] switch
163+
0 => _vehicleController.data.bus[Channel.Vehicle][VehicleData.GearboxMode] switch
170164
{
171165
(int)Gearbox.AutomaticGear.P => "P",
172166
(int)Gearbox.AutomaticGear.N => "N",

Assets/AWSIM/Scripts/UI/VehicleDashboard.cs.meta

+1-1
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

Assets/AWSIM/Scripts/Vehicles/VPP Integration/AutowareVPPAdapter.cs

+30-1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
using System;
22
using System.Collections.Generic;
3+
using AWSIM.Scripts.UI;
34
using AWSIM.Scripts.Vehicles.VPP_Integration.Enums;
45
using AWSIM.Scripts.Vehicles.VPP_Integration.IVehicleControlModes;
56
using UnityEngine;
@@ -130,7 +131,7 @@ public class AutowareVPPAdapter : MonoBehaviour
130131
// RViz2 Update position variables
131132
[Header("RViz2 Update Position")]
132133
[SerializeField]
133-
private float _updatePositionOffsetY = 1.33f;
134+
private float _updatePositionOffsetY = 0.5f;
134135

135136
[SerializeField] private float _updatePositionRayOriginY = 1000f;
136137

@@ -147,6 +148,9 @@ public class AutowareVPPAdapter : MonoBehaviour
147148
private const float VppToAutowareMultiplier = 0.0001f;
148149
private const int AutowareToVppMultiplier = 10000;
149150

151+
// Event holders to subscribe
152+
private EgoVehiclePositionManager _egoVehiclePositionManager;
153+
150154
private void Awake()
151155
{
152156
//TODO: Implement the control mode switch from simulator (mozzz)
@@ -172,6 +176,13 @@ private void Start()
172176
// reset vpp stuff for multi-scene loading (no idea why, but it works)
173177
_vehicleController.enabled = false;
174178
_vehicleController.enabled = true;
179+
180+
// Subscribe to events
181+
_egoVehiclePositionManager = FindObjectOfType<EgoVehiclePositionManager>();
182+
if (_egoVehiclePositionManager != null)
183+
{
184+
_egoVehiclePositionManager.OnEgoReset += ResetEgoPosition;
185+
}
175186
}
176187

177188
// private void Update()
@@ -341,6 +352,8 @@ private void UpdateEgoPosition()
341352
{
342353
PositionInput = new Vector3(PositionInput.x, hit.point.y + _updatePositionOffsetY, PositionInput.z);
343354
_vehicleController.HardReposition(PositionInput, RotationInput);
355+
_vehicleController.data.bus[Channel.Input][InputData.AutomaticGear] = (int)Gearbox.AutomaticGear.P;
356+
_cameraController.ResetCamera();
344357
}
345358
else
346359
{
@@ -349,6 +362,16 @@ private void UpdateEgoPosition()
349362
}
350363
}
351364

365+
/// <summary>
366+
/// Reset the ego vehicle to the spawn point.
367+
/// </summary>
368+
private void ResetEgoPosition(Vector3 position, Quaternion rotation)
369+
{
370+
_vehicleController.HardReposition(position, rotation, true);
371+
_vehicleController.data.bus[Channel.Input][InputData.AutomaticGear] = (int)Gearbox.AutomaticGear.P;
372+
_cameraController.ResetCamera();
373+
}
374+
352375
// TODO: Method to switch control mode based on user input (mozzz)
353376
// Currently it is updated from UI with keyboard toggle.
354377
private void UserSwitchControlMode()
@@ -380,5 +403,11 @@ private void PedalCalibrationMode()
380403
_brakeAmount = 0;
381404
}
382405
}
406+
407+
private void OnDestroy()
408+
{
409+
// Unsubscribe from events
410+
_egoVehiclePositionManager.OnEgoReset -= ResetEgoPosition;
411+
}
383412
}
384413
}

Assets/AWSIM/Scripts/Vehicles/VPP Integration/AutowareVPPAdapter.cs.meta

+1-1
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

0 commit comments

Comments
 (0)