Skip to content

Commit dcf6544

Browse files
committed
fixed some import errors. added urdf import documentation.
1 parent dff8f64 commit dcf6544

File tree

4 files changed

+102
-13
lines changed

4 files changed

+102
-13
lines changed

README.md

Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
- [Running Image Segmentation Test](#running-image-segmentation-test)
1414
- [Export URDF](#export-urdf)
1515
- [Import URDF](#import-urdf)
16+
- [LEO Robot Example](#leo-robot-example)
1617

1718
ZeroSim is a robotics simulation engine built on the easy to use [Unity 3D](https://unity.com/) development platform and the power of the [Robotics Operating System (ROS)](https://www.ros.org/). ZeroSim is designed for ease of use and rapid development of all sorts of robotics and simulation -- from warehouses and industrial settings, to farming and outdoors -- from robotic arms to ground and drone based mobile robots.
1819

@@ -220,3 +221,78 @@ roslaunch zero_sim_ros basic_unity_editor.launch
220221
### Import URDF
221222

222223
1. Right click and select `ZeroSim --> Import URDF...`
224+
225+
#### LEO Robot Example
226+
227+
1. Clone the Leo robot: `git clone --recursive https://github.com/LeoRover/leo_common.git`
228+
2. Checkout Melodic version. `cd leo_common && git checkout melodic`.
229+
3. Startup ZeroSim Docker mounting the LEO directory:
230+
231+
```
232+
233+
# make sure you are in parent directory for `leo_common`
234+
cd ..
235+
236+
# run docker
237+
docker run -it --rm \
238+
--publish=9090:9090 \
239+
--publish=11311:11311 \
240+
--publish=8083:8083 \
241+
--publish=80:80 \
242+
--publish=5678:5678 \
243+
--name my_zerosim_vnc_docker \
244+
--volume=$(pwd)/leo_common/:/catkin_ws/src/leo_common/ \
245+
zerodog/zerosim_ros_vnc:latest \
246+
bash
247+
```
248+
4. In the Docker command prompt build the catkin workspace:
249+
250+
```
251+
source devel/setup.bash
252+
catkin build
253+
# Make sure to source ROS again to get the new LEO robot
254+
source devel/setup.bash
255+
```
256+
5. In the Docker command prompt Run XAcro on the LEO robot to get the URDF:
257+
258+
```
259+
rosrun xacro xacro src/leo_common/leo_description/urdf/leo_sim.urdf.xacro > /tmp/leo_sim.urdf
260+
```
261+
6. Convert LEO robot meshes to .obj for Unity. In the Docker command prompt:
262+
263+
```
264+
/zerosim_tools/convert_meshes_to_obj.sh ./src/leo_common/leo_description/models
265+
```
266+
267+
7. Copy URDF from Docker to host:
268+
269+
```
270+
# create a directory to store the URDF and meshes
271+
mkdir my_leo_robot
272+
273+
# copy the URDF
274+
docker cp my_zerosim_vnc_docker:/tmp/leo_sim.urdf ./my_leo_robot
275+
```
276+
277+
8. Copy Meshes from Docker to host:
278+
279+
```
280+
# Note we are preserving the path
281+
docker cp my_zerosim_vnc_docker:/catkin_ws/src/leo_common/leo_description/models ./my_leo_robot/leo_description/models
282+
```
283+
284+
9. Fix the URDF paths to the meshes:
285+
286+
```
287+
# First fix up the .DAEs to point to the OBJs
288+
sed -i 's#.dae#.obj#g' my_leo_robot/leo_sim.urdf
289+
290+
# The fix up the .STLs to point to the OBJs
291+
sed -i 's#.stl#.obj#g' my_leo_robot/leo_sim.urdf
292+
293+
# Now remove the `package://` because we are using the filesystem
294+
sed -i 's#package://#./#g' my_leo_robot/leo_sim.urdf
295+
296+
```
297+
298+
10. In Unity import URDF by: Right click and select `ZeroSim --> Import URDF...`

Runtime/Scripts/Util/ImportExport/ZOImportOBJ.cs

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,7 @@ protected static Material[] ImportMTLFile(string mtlFilePath) {
109109
}
110110

111111
public static GameObject Import(string objFilePath, bool splitByMaterial ) {
112+
Debug.Log($"INFO: Importing OBJ file: {objFilePath}");
112113
using (StreamReader streamReader = new StreamReader(objFilePath)) {
113114
return Import(streamReader, Path.GetFileNameWithoutExtension(objFilePath), Path.GetDirectoryName(objFilePath), splitByMaterial);
114115
}

Runtime/Scripts/Util/ImportExport/ZOImportURDF.cs

Lines changed: 24 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -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

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.17",
3+
"version": "0.1.18",
44
"displayName": "ZeroSim",
55
"description": "ZeroSim ROS robotic simulator in Unity.",
66
"unity": "2020.1",

0 commit comments

Comments
 (0)