Skip to content

Commit 1a4d31b

Browse files
committed
fixed diff drive controller crash when not named. Fixed diff drive control disconnect event.
1 parent 3fef9ce commit 1a4d31b

File tree

2 files changed

+29
-10
lines changed

2 files changed

+29
-10
lines changed

Runtime/Scripts/ROS/Unity/Controllers/ZODifferentialDriveController.cs

Lines changed: 24 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ public string Name {
5353
public Rigidbody ConnectedRigidBody {
5454
get { return _connectedBody.GetComponent<Rigidbody>(); }
5555
}
56-
[SerializeField][ZOReadOnly] public ZOHingeJoint _rightWheelMotor;
56+
[SerializeField] [ZOReadOnly] public ZOHingeJoint _rightWheelMotor;
5757

5858
/// <summary>
5959
/// Hinge joint that drives the right wheel.
@@ -63,8 +63,8 @@ public ZOHingeJoint RightWheelMotor {
6363
get => _rightWheelMotor;
6464
set => _rightWheelMotor = value;
6565
}
66-
67-
[SerializeField][ZOReadOnly] public ZOHingeJoint _leftWheelMotor;
66+
67+
[SerializeField] [ZOReadOnly] public ZOHingeJoint _leftWheelMotor;
6868

6969
/// <summary>
7070
/// Hinge joint that drive the left wheel.
@@ -113,12 +113,30 @@ public string Type {
113113
}
114114
}
115115

116+
void OnValidate() {
117+
// make sure we have a name
118+
if (string.IsNullOrEmpty(_name)) {
119+
_name = gameObject.name + "_" + Type;
120+
}
121+
122+
}
123+
124+
protected override void ZOAwake() {
125+
base.ZOAwake();
126+
127+
// make sure we have a name
128+
if (string.IsNullOrEmpty(_name)) {
129+
_name = gameObject.name + "_" + Type;
130+
}
131+
132+
}
116133

117134
// Start is called before the first frame update
118135
protected override void ZOStart() {
136+
base.ZOStart();
119137
// auto-connect to ROS Bridge connection and disconnect events
120138
ZOROSUnityManager.Instance.ROSBridgeConnectEvent += OnROSBridgeConnected;
121-
ZOROSUnityManager.Instance.ROSBridgeDisconnectEvent += OnROSBridgeConnected;
139+
ZOROSUnityManager.Instance.ROSBridgeDisconnectEvent += OnROSBridgeDisconnected;
122140

123141
if (ZOROSBridgeConnection.Instance.IsConnected) {
124142
// subscribe to Twist Message
@@ -132,7 +150,7 @@ protected override void ZOStart() {
132150

133151
protected override void ZOOnDestroy() {
134152
ZOROSUnityManager.Instance.ROSBridgeConnectEvent -= OnROSBridgeConnected;
135-
ZOROSUnityManager.Instance.ROSBridgeDisconnectEvent -= OnROSBridgeConnected;
153+
ZOROSUnityManager.Instance.ROSBridgeDisconnectEvent -= OnROSBridgeDisconnected;
136154
}
137155

138156
protected override void ZOFixedUpdate() {
@@ -143,7 +161,7 @@ protected override void ZOFixedUpdate() {
143161
} else {
144162
AngularVelocity = (float)_twistMessage.angular.z * Mathf.Rad2Deg;
145163
}
146-
164+
147165
}
148166
protected override void ZOFixedUpdateHzSynchronized() {
149167

Runtime/Scripts/ROS/Unity/ZOROSUnityManager.cs

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -164,7 +164,7 @@ public void BroadcastTransform(TransformStampedMessage transformStamped) {
164164
public static ZOROSUnityManager Instance {
165165
get => _instance;
166166
}
167-
167+
168168
#endregion // Singleton
169169

170170

@@ -195,7 +195,7 @@ public AssetBundle DefaultAssets {
195195
#region Simulation Clock
196196

197197
ClockMessage _clockMessage = new ClockMessage();
198-
198+
199199
/// <summary>
200200
/// sim
201201
/// </summary>
@@ -244,7 +244,7 @@ void Start() {
244244

245245

246246
ROSBridgeConnection.Serialization = _serializationType;
247-
ROSBridgeConnection.ROSBridgeConnectEvent += delegate(ZOROSBridgeConnection rosBridge) {
247+
ROSBridgeConnection.ROSBridgeConnectEvent += delegate (ZOROSBridgeConnection rosBridge) {
248248
Debug.Log("INFO: Connected to ROS Bridge");
249249

250250
// advertise the transform broadcast
@@ -289,7 +289,7 @@ void Start() {
289289

290290
// run async task. if cannot connect wait for a couple of seconds and try again
291291
ROSBridgeConnection.Port = Port;
292-
ROSBridgeConnection.Hostname = Hostname;
292+
ROSBridgeConnection.Hostname = Hostname;
293293
Task rosBridgeConnectionTask = Task.Run(async () => {
294294
await ROSBridgeConnection.ConnectAsync();
295295
});
@@ -298,6 +298,7 @@ void Start() {
298298

299299
}
300300

301+
301302
private void OnDestroy() {
302303
ROSBridgeConnection.UnAdvertise("/tf");
303304
// ROSBridgeConnection.UnAdvertiseService(_namespace + "/spawn_zosim_model");

0 commit comments

Comments
 (0)