@@ -136,7 +136,7 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
136136
137137 XmlNode xmlBox = xmlGeom . GetChildByName ( "box" ) ;
138138 if ( xmlBox != null ) {
139- collisionGeo = new GameObject ( "box_collider" ) ;
139+ collisionGeo = new GameObject ( "box_collider" ) ;
140140 BoxCollider boxCollider = collisionGeo . AddComponent < BoxCollider > ( ) ;
141141 Vector3 size = xmlBox . Attributes [ "size" ] . Value . FromURDFStringToVector3 ( ) ;
142142
@@ -155,7 +155,7 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
155155
156156 GameObject . DestroyImmediate ( collisionGeo . GetComponent < MeshRenderer > ( ) ) ;
157157 GameObject . DestroyImmediate ( collisionGeo . GetComponent < MeshFilter > ( ) ) ;
158-
158+
159159 }
160160
161161 XmlNode xmlSphere = xmlGeom . GetChildByName ( "sphere" ) ;
@@ -259,9 +259,14 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
259259 if ( xmlWorkingJoint != null ) {
260260 // set the transform
261261 XmlNode xmlOrigin = xmlWorkingJoint . GetChildByName ( "origin" ) ;
262- Tuple < Vector3 , Quaternion > transform = OriginXMLToUnity ( xmlOrigin ) ;
263- linkChild . transform . localPosition = transform . Item1 ;
264- linkChild . transform . localRotation = transform . Item2 ;
262+ Tuple < Vector3 , Quaternion > transform = new Tuple < Vector3 , Quaternion > ( Vector3 . zero , Quaternion . identity ) ;
263+ if ( xmlOrigin != null ) {
264+ transform = OriginXMLToUnity ( xmlOrigin ) ;
265+ linkChild . transform . localPosition = transform . Item1 ;
266+ linkChild . transform . localRotation = transform . Item2 ;
267+ } else {
268+ Debug . LogWarning ( "WARNING: Origin is null" ) ;
269+ }
265270
266271 // add rigidbody components
267272 Rigidbody childRigidBody = null ;
@@ -300,7 +305,7 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
300305 if ( childRigidBody == null ) {
301306 childRigidBody = linkChild . AddComponent < Rigidbody > ( ) ;
302307 }
303-
308+
304309 }
305310 hingeJoint . ConnectedBody = childRigidBody ;
306311 hingeJoint . Anchor = transform . Item1 ;
@@ -328,15 +333,22 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
328333
329334 protected static Tuple < Vector3 , Quaternion > OriginXMLToUnity ( XmlNode xmlOrigin ) {
330335 Vector3 translation = Vector3 . zero ;
331- string xyz = xmlOrigin . Attributes [ "xyz" ] . Value ;
332- if ( xyz != null && xyz != "" ) {
333- translation = xyz . FromURDFStringToVector3 ( ) . Ros2Unity ( ) ;
336+ if ( xmlOrigin . Attributes [ "xyz" ] != null ) {
337+ string xyz = xmlOrigin . Attributes [ "xyz" ] . Value ;
338+
339+ if ( xyz != null && xyz != "" ) {
340+ translation = xyz . FromURDFStringToVector3 ( ) . Ros2Unity ( ) ;
341+ }
342+
334343 }
335344
336345 Quaternion rotation = Quaternion . identity ;
337- string rpy = xmlOrigin . Attributes [ "rpy" ] . Value ;
338- if ( rpy != null && rpy != "" ) {
339- rotation = rpy . FromURDFStringToVector3 ( ) . RosRollPitchYawToQuaternion ( ) ;
346+ if ( xmlOrigin . Attributes [ "rpy" ] != null ) {
347+ string rpy = xmlOrigin . Attributes [ "rpy" ] . Value ;
348+ if ( rpy != null && rpy != "" ) {
349+ rotation = rpy . FromURDFStringToVector3 ( ) . RosRollPitchYawToQuaternion ( ) ;
350+ }
351+
340352 }
341353 Tuple < Vector3 , Quaternion > transform = new Tuple < Vector3 , Quaternion > ( translation , rotation ) ;
342354
0 commit comments