Skip to content

Commit f034e4c

Browse files
committed
working obj mesh import for urdf
1 parent 21c0117 commit f034e4c

File tree

3 files changed

+21
-23
lines changed

3 files changed

+21
-23
lines changed

Runtime/Scripts/Util/ImportExport/ZOImportOBJ.cs

Lines changed: 6 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ protected static Material[] ImportMTLFile(string mtlFilePath) {
6060
currentMaterial.name = data;
6161
} else if (lineComponents[0] == "Kd") {
6262
currentMaterial.SetColor("_Color", ParseColor(lineComponents));
63-
} else if (lineComponents[0] == "map_Kd") {
63+
} else if (lineComponents[0] == "map_Kd" && lineComponents.Length > 1) {
6464
string texturePath = Path.Combine(workingDirectory, lineComponents[1]);
6565
string textureType = Path.GetExtension(texturePath);
6666
if (textureType == ".png" || textureType == ".jpg") {
@@ -240,14 +240,9 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
240240
if (objectNames.Count == 0)
241241
objectNames.Add("default");
242242

243-
//build objects
244-
GameObject parentObject = new GameObject(meshName);
245-
246-
243+
GameObject meshGameObject = new GameObject(meshName);
247244
foreach (string obj in objectNames) {
248-
GameObject subObject = new GameObject(obj);
249-
subObject.transform.parent = parentObject.transform;
250-
subObject.transform.localScale = new Vector3(-1, 1, 1);
245+
meshGameObject.transform.localScale = new Vector3(-1, 1, 1);
251246
Mesh m = new Mesh();
252247
m.name = obj;
253248
List<Vector3> processedVertices = new List<Vector3>();
@@ -273,9 +268,7 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
273268

274269
for (int i = 0; i < indexes.Length; i++) {
275270
int idx = indexes[i];
276-
//build remap table
277271
if (remapTable.ContainsKey(idx)) {
278-
//ezpz
279272
indexes[i] = remapTable[idx];
280273
} else {
281274
processedVertices.Add(uvertices[idx]);
@@ -306,8 +299,8 @@ public static GameObject Import(StreamReader streamReader, string meshName, stri
306299
m.RecalculateBounds();
307300
;
308301

309-
MeshFilter mf = subObject.AddComponent<MeshFilter>();
310-
MeshRenderer mr = subObject.AddComponent<MeshRenderer>();
302+
MeshFilter mf = meshGameObject.AddComponent<MeshFilter>();
303+
MeshRenderer mr = meshGameObject.AddComponent<MeshRenderer>();
311304

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

332325
}
333326

334-
return parentObject;
327+
return meshGameObject;
335328
}
336329

337330
}

Runtime/Scripts/Util/ImportExport/ZOImportURDF.cs

Lines changed: 14 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -17,20 +17,16 @@ namespace ZO.ImportExport {
1717

1818
public class ZOImportURDF {
1919

20-
public static string WorkingDirectory {
21-
get; set;
22-
} = ".";
2320

2421
public static ZOSimDocumentRoot Import(string urdfFilePath) {
2522
using (StreamReader streamReader = new StreamReader(urdfFilePath)) {
26-
WorkingDirectory = Path.GetDirectoryName(urdfFilePath);
2723
XmlDocument xmlDocument = new XmlDocument();
2824
xmlDocument.Load(streamReader);
29-
return Import(xmlDocument);
25+
return Import(xmlDocument, Path.GetDirectoryName(urdfFilePath));
3026
}
3127
}
3228

33-
public static ZOSimDocumentRoot Import(XmlDocument xmlDocument) {
29+
public static ZOSimDocumentRoot Import(XmlDocument xmlDocument, string workingDirectory) {
3430
XmlNode robot = xmlDocument.GetChildByName("robot");
3531

3632
GameObject rootObject = new GameObject(robot.Attributes["name"].Value);
@@ -94,7 +90,16 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument) {
9490

9591
XmlNode xmlMesh = xmlGeom.GetChildByName("mesh");
9692
if (xmlMesh != null) {
97-
// TODO
93+
string meshFileName = xmlMesh.Attributes["filename"].Value;
94+
string meshFilePath = Path.Combine(workingDirectory, meshFileName);
95+
visualGeo = ZOImportOBJ.Import(meshFilePath);
96+
if (xmlMesh.Attributes["scale"] != null) {
97+
Vector3 scale = xmlMesh.Attributes["scale"].Value.FromURDFStringToVector3().Ros2UnityScale();
98+
visualGeo.transform.localScale = new Vector3(visualGeo.transform.localScale.x * scale.x, visualGeo.transform.localScale.y * scale.y, visualGeo.transform.localScale.z * scale.z);
99+
}
100+
101+
visualGeo.transform.localRotation = Quaternion.Euler(270, 90, 0);
102+
98103
}
99104
if (visualGeo != null) {
100105
// set parent
@@ -107,8 +112,8 @@ public static ZOSimDocumentRoot Import(XmlDocument xmlDocument) {
107112
// set transform
108113
XmlNode xmlOrigin = xmlVisual.GetChildByName("origin");
109114
Tuple<Vector3, Quaternion> transform = OriginXMLToUnity(xmlOrigin);
110-
visualGeo.transform.localPosition = transform.Item1;
111-
visualGeo.transform.localRotation = transform.Item2;
115+
visualGeo.transform.localPosition += transform.Item1;
116+
visualGeo.transform.localRotation *= transform.Item2;
112117

113118
}
114119

package.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
{
22
"name": "com.fsstudio.zerosim",
3-
"version": "0.1.10",
3+
"version": "0.1.11",
44
"displayName": "ZeroSim",
55
"description": "ZeroSim ROS robotic simulator in Unity.",
66
"unity": "2020.1",

0 commit comments

Comments
 (0)