Skip to content

Commit 329e98a

Browse files
committed
pretty good working urdf import tested with UR10
1 parent 4f9fc1a commit 329e98a

File tree

5 files changed

+10376
-1986
lines changed

5 files changed

+10376
-1986
lines changed

Editor/ZOZeroSimMenu.cs

Lines changed: 24 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
using UnityEditor;
33
using ZO.Document;
44
using ZO.ImportExport;
5+
using System.IO;
56
namespace ZO.Editor {
67
public static class ZOZeroSimMenu {
78
[MenuItem("GameObject/ZeroSim/New Robot", false, 0)]
@@ -44,24 +45,45 @@ static void CreateZeroSimRobot(MenuCommand menuCommand) {
4445
[MenuItem("GameObject/ZeroSim/Import URDF...", false, 0)]
4546
static void ImportURDF(MenuCommand menuCommand) {
4647
string filePath = EditorUtility.OpenFilePanel("Import URDF", ".", "urdf");
48+
string saveToDirectory = EditorUtility.OpenFolderPanel("Save to folder...", Path.Combine(Path.GetDirectoryName(Application.dataPath), "Assets"), "");
4749

4850
if (filePath.Length == 0) {
4951
return;
5052
}
5153

52-
ZOImportURDF.Import(filePath);
54+
ZOSimDocumentRoot documentRoot = ZOImportURDF.Import(filePath);
55+
5356

5457
}
5558

5659
[MenuItem("GameObject/ZeroSim/Import OBJ...", false, 0)]
5760
static void ImportOBJ(MenuCommand menuCommand) {
5861
string filePath = EditorUtility.OpenFilePanel("Import OBJ", ".", "obj");
62+
string saveToDirectory = EditorUtility.OpenFolderPanel("Save to folder...", Path.Combine(Path.GetDirectoryName(Application.dataPath), "Assets"), "");
5963

6064
if (filePath.Length == 0) {
6165
return;
6266
}
6367

64-
ZOImportOBJ.Import(filePath);
68+
GameObject go = ZOImportOBJ.Import(filePath);
69+
70+
// build a prefab from the GameObject
71+
MeshFilter[] meshFilters = go.GetComponentsInChildren<MeshFilter>();
72+
73+
foreach (MeshFilter meshFilter in meshFilters) {
74+
string meshAssetPath = Path.Combine(saveToDirectory, $"{meshFilter.name}.asset");
75+
meshAssetPath = meshAssetPath.Substring(Application.dataPath.Length);
76+
Debug.Log("INFO: saving to relative path: " + meshAssetPath);
77+
Mesh msh = new Mesh();
78+
msh.vertices = meshFilter.sharedMesh.vertices;
79+
msh.triangles = meshFilter.sharedMesh.triangles;
80+
msh.uv = meshFilter.sharedMesh.uv;
81+
msh.uv2 = meshFilter.sharedMesh.uv2;
82+
msh.RecalculateNormals();
83+
msh.RecalculateBounds();
84+
85+
AssetDatabase.CreateAsset(msh, "Assets/" + meshAssetPath);
86+
}
6587

6688
}
6789

Runtime/Scripts/Document/ZOSimOccurrence.cs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ public ZOSimDocumentRoot DocumentRoot {
4949
}
5050
}
5151

52-
Assert.IsNotNull(_documentRoot, "ERROR: a ZOSimOccurrence needs a ZOSimDocumentRoot at the root of the hierarchy.");
52+
Debug.LogWarning("WARNING: a ZOSimOccurrence needs a ZOSimDocumentRoot at the root of the hierarchy.");
5353

5454
return _documentRoot;
5555
}

Runtime/Scripts/Util/ImportExport/ZOImportOBJ.cs

Lines changed: 38 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -9,14 +9,10 @@
99

1010
namespace ZO.ImportExport {
1111
public class ZOImportOBJ {
12-
public static string WorkingDirectory {
13-
get; set;
14-
} = ".";
1512

16-
public static string FileName {
13+
public static bool SplitByMaterial {
1714
get; set;
18-
} = "temp";
19-
15+
} = true;
2016

2117
struct OBJFace {
2218
public string materialName;
@@ -64,11 +60,11 @@ protected static Material[] ImportMTLFile(string mtlFilePath) {
6460
string texturePath = Path.Combine(workingDirectory, lineComponents[1]);
6561
string textureType = Path.GetExtension(texturePath);
6662
if (textureType == ".png" || textureType == ".jpg") {
67-
Texture2D texture = new Texture2D(1,1);
63+
Texture2D texture = new Texture2D(1, 1);
6864
texture.LoadImage(File.ReadAllBytes(texturePath));
6965
currentMaterial.SetTexture("_MainTex", texture);
7066
}
71-
67+
7268
} else if (lineComponents[0] == "map_Bump") {
7369
// TODO
7470
} else if (lineComponents[0] == "Ks") {
@@ -133,7 +129,7 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
133129
List<string> objectNames = new List<string>();
134130
Dictionary<string, int> hashtable = new Dictionary<string, int>();
135131
List<OBJFace> faceList = new List<OBJFace>();
136-
string cmaterial = "";
132+
string cmaterial = "default";
137133
string cmesh = "default";
138134
//CACHE
139135
Material[] materials = null;
@@ -149,7 +145,7 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
149145
string mtlFilePath = Path.Combine(workingDirectory, lineComponents[1]);
150146
materials = ImportMTLFile(mtlFilePath);
151147

152-
} else if ((lineComponents[0] == "g" || lineComponents[0] == "o")) {
148+
} else if ((lineComponents[0] == "g" || lineComponents[0] == "o") && SplitByMaterial == false) {
153149
cmesh = data;
154150
if (!objectNames.Contains(cmesh)) {
155151
objectNames.Add(cmesh);
@@ -160,6 +156,12 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
160156
materialNames.Add(cmaterial);
161157
}
162158

159+
if (SplitByMaterial) {
160+
if (!objectNames.Contains(cmaterial)) {
161+
objectNames.Add(cmaterial);
162+
}
163+
}
164+
163165
} else if (lineComponents[0] == "v") {
164166
//VERTEX
165167
vertices.Add(ParseVector3(lineComponents));
@@ -222,13 +224,13 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
222224
OBJFace f1 = new OBJFace();
223225
f1.materialName = cmaterial;
224226
f1.indexes = new int[] { indexes[0], indexes[1], indexes[2] };
225-
f1.meshName = cmesh;
227+
f1.meshName = (SplitByMaterial) ? cmaterial : cmesh;
226228
faceList.Add(f1);
227229
if (indexes.Length > 3) {
228230

229231
OBJFace f2 = new OBJFace();
230232
f2.materialName = cmaterial;
231-
f2.meshName = cmesh;
233+
f2.meshName = (SplitByMaterial) ? cmaterial : cmesh;;
232234
f2.indexes = new int[] { indexes[2], indexes[3], indexes[0] };
233235
faceList.Add(f2);
234236
}
@@ -237,12 +239,21 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
237239
}
238240
}
239241

240-
if (objectNames.Count == 0)
242+
if (objectNames.Count == 0) {
241243
objectNames.Add("default");
244+
}
242245

243-
GameObject meshGameObject = new GameObject(meshName);
246+
if (materialNames.Count == 0) {
247+
materialNames.Add("default");
248+
}
249+
250+
GameObject parentGameObject = new GameObject(meshName);
251+
252+
// GameObject meshGameObject = new GameObject(meshName);
244253
foreach (string obj in objectNames) {
245-
meshGameObject.transform.localScale = new Vector3(-1, 1, 1);
254+
GameObject childGameObject = new GameObject(obj);
255+
childGameObject.transform.parent = parentGameObject.transform;
256+
childGameObject.transform.localScale = new Vector3(-1, 1, 1);
246257
Mesh m = new Mesh();
247258
m.name = obj;
248259
List<Vector3> processedVertices = new List<Vector3>();
@@ -253,6 +264,7 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
253264
List<string> meshMaterialNames = new List<string>();
254265

255266
OBJFace[] objFaces = faceList.Where(x => x.meshName == obj).ToArray();
267+
256268
foreach (string mn in materialNames) {
257269
OBJFace[] faces = objFaces.Where(x => x.materialName == mn).ToArray();
258270
if (faces.Length > 0) {
@@ -297,10 +309,17 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
297309
m.RecalculateNormals();
298310
}
299311
m.RecalculateBounds();
300-
;
301312

302-
MeshFilter mf = meshGameObject.AddComponent<MeshFilter>();
303-
MeshRenderer mr = meshGameObject.AddComponent<MeshRenderer>();
313+
MeshFilter mf = childGameObject.GetComponent<MeshFilter>();
314+
if (mf == null) {
315+
mf = childGameObject.AddComponent<MeshFilter>();
316+
}
317+
MeshRenderer mr = childGameObject.GetComponent<MeshRenderer>();
318+
if (mr == null) {
319+
mr = childGameObject.AddComponent<MeshRenderer>();
320+
}
321+
322+
304323

305324
Material[] processedMaterials = new Material[meshMaterialNames.Count];
306325
for (int i = 0; i < meshMaterialNames.Count; i++) {
@@ -324,7 +343,7 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
324343

325344
}
326345

327-
return meshGameObject;
346+
return parentGameObject;
328347
}
329348

330349
}

Runtime/Scripts/Util/ImportExport/ZOImportURDF.cs

Lines changed: 15 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -97,23 +97,25 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
9797
Vector3 scale = xmlMesh.Attributes["scale"].Value.FromURDFStringToVector3().Ros2UnityScale();
9898
visualGeo.transform.localScale = new Vector3(visualGeo.transform.localScale.x * scale.x, visualGeo.transform.localScale.y * scale.y, visualGeo.transform.localScale.z * scale.z);
9999
}
100-
100+
101101
visualGeo.transform.localRotation = Quaternion.Euler(270, 90, 0);
102-
102+
103103
}
104104
if (visualGeo != null) {
105105
// set parent
106106
visualGeo.transform.SetParent(goVisualsEmpty.transform);
107-
string visualName = xmlVisual.Attributes["name"].Value;
108-
if (visualName != null) {
109-
visualGeo.name = visualName;
107+
if (xmlVisual.Attributes["name"] != null) {
108+
visualGeo.name = xmlVisual.Attributes["name"].Value;
110109
}
111110

112111
// set transform
113112
XmlNode xmlOrigin = xmlVisual.GetChildByName("origin");
114-
Tuple<Vector3, Quaternion> transform = OriginXMLToUnity(xmlOrigin);
115-
visualGeo.transform.localPosition += transform.Item1;
116-
visualGeo.transform.localRotation *= transform.Item2;
113+
if (xmlOrigin != null) {
114+
Tuple<Vector3, Quaternion> transform = OriginXMLToUnity(xmlOrigin);
115+
visualGeo.transform.localPosition += transform.Item1;
116+
visualGeo.transform.localRotation *= transform.Item2;
117+
118+
}
117119

118120
}
119121

@@ -171,7 +173,7 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
171173
XmlNode xmlInertial = xmlChildLinkNode.GetChildByName("inertial");
172174
if (xmlInertial != null) {
173175
childRigidBody = linkChild.AddComponent<Rigidbody>();
174-
176+
175177
float mass = 1.0f;
176178
float.TryParse(xmlInertial.GetChildByName("mass").Attributes["value"].Value, out mass);
177179
childRigidBody.mass = mass;
@@ -180,7 +182,7 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
180182

181183
xmlInertial = xmlParentLinkNode.GetChildByName("inertial");
182184
parentRigidBody = linkParent.GetComponent<Rigidbody>();
183-
if (xmlInertial != null && parentRigidBody == null) {
185+
if (xmlInertial != null && parentRigidBody == null) {
184186
parentRigidBody = linkParent.AddComponent<Rigidbody>();
185187

186188
float mass = 1.0f;
@@ -214,6 +216,9 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDi
214216
}
215217

216218
protected static Tuple<Vector3, Quaternion> OriginXMLToUnity(XmlNode xmlOrigin) {
219+
if (xmlOrigin == null) {
220+
Debug.Log("BLAH");
221+
}
217222
Vector3 translation = Vector3.zero;
218223
string xyz = xmlOrigin.Attributes["xyz"].Value;
219224
if (xyz != null && xyz != "") {

0 commit comments

Comments
 (0)