Skip to content

Commit

Permalink
Cleanup Unitree Z1.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 594719455
Change-Id: I5d7b088bc60472fc79470bbd01490086d7b659de
  • Loading branch information
kevinzakka authored and copybara-github committed Dec 31, 2023
1 parent 9e3c4e4 commit a099b54
Show file tree
Hide file tree
Showing 5 changed files with 70 additions and 42 deletions.
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,7 @@ Menagerie, see [CONTRIBUTING](CONTRIBUTING.md).
| [xArm7](ufactory_xarm7/README.md)|[<img src="ufactory_xarm7/xarm7.png" width="400">](ufactory_xarm7/README.md)|C|
| [Lite 6](ufactory_lite6/README.md)|[<img src="ufactory_lite6/lite6.png" width="400">](ufactory_lite6/README.md)|C|
| [ViperX 300 6DOF](trossen_vx300s/README.md)|[<img src="trossen_vx300s/vx300s.png" width="400">](trossen_vx300s/README.md)|A|
| [Unitree Z1](unitree_z1/README.md)|[<img src="unitree_z1/z1.png" width="400">](unitree_z1/README.md)|B|
| Mobile Manipulators| | |
| [Google Robot](google_robot/README.md)|[<img src="google_robot/robot.png" width="400">](google_robot/README.md)|B|
| [Stretch 2](hello_robot_stretch/README.md)|[<img src="hello_robot_stretch/stretch.png" width="400">](hello_robot_stretch/README.md)|C|
Expand Down
15 changes: 11 additions & 4 deletions unitree_z1/README.md
Original file line number Diff line number Diff line change
@@ -1,19 +1,26 @@
# Unitree Z1 description (MJCF)

Requires MuJoCo 2.3.3 or later.

## Overview

This package contains robot description (MJCF) of the [Z1 manipulator](https://www.unitree.com/z1/). It is derivede from the [publicly available URDF description](https://github.com/unitreerobotics/unitree_ros/blob/master/robots/z1_description/xacro/z1.urdf)
This package contains a simplified robot description (MJCF) of the [Z1
manipulator](https://www.unitree.com/z1/) developed by [Unitree
Robotics](https://www.unitree.com/). It is derived from the [publicly available
URDF
description](https://github.com/unitreerobotics/unitree_ros/blob/master/robots/z1_description/).

<p float="left">
<img src="z1.png" width="400">
</p>

## URDF → MJCF derivation steps

1. Added `<mujoco><compiler balanceinertia="true" discardvisual="false"/></mujoco>` to the URDF's `<robot>` clause in order to preserve visual geometries.
1. Added `<mujoco><compiler discardvisual="false" fusestatic="false"/></mujoco>` to the URDF's `<robot>` clause in order to preserve visual geometries.
2. Loaded the URDF into MuJoCo and saved a corresponding MJCF.
3. Manually edited the MJCF to use meshes for collision too.
4. Added `scene.xml` which includes the robot, with a textured groundplane, skybox and haze.e.
3. Manually edited the MJCF to extract common properties into the `<default>` section.
4. Added position-control actuators.
5. Added `scene.xml` which includes the robot, with a textured groundplane, skybox, and haze.

## License

Expand Down
34 changes: 17 additions & 17 deletions unitree_z1/scene.xml
Original file line number Diff line number Diff line change
@@ -1,23 +1,23 @@
<mujoco model="z1 scene">
<include file="z1.xml"/>
<include file="z1.xml"/>

<statistic center="0 0 0.1" extent="0.8"/>
<statistic center="0 0 0.1" extent="0.6"/>

<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="120" elevation="-20"/>
</visual>
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="120" elevation="-20"/>
</visual>

<asset>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3"
markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
</asset>
<asset>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3"
markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
</asset>

<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
</worldbody>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
</worldbody>
</mujoco>
Binary file modified unitree_z1/z1.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
62 changes: 41 additions & 21 deletions unitree_z1/z1.xml
Original file line number Diff line number Diff line change
@@ -1,59 +1,74 @@
<mujoco model="z1">
<compiler angle="radian" meshdir="assets"/>

<option integrator="implicitfast"/>

<default>
<default class="z1">
<joint damping="1" frictionloss="1"/>
<general biastype="affine" gainprm="1000" biasprm="0 -1000 -100" forcerange="-30 30"/>
<default class="visual">
<geom type="mesh"/>
<geom type="mesh" group="2" contype="0" conaffinity="0"/>
</default>
<default class="collision">
<geom type="cylinder" group="3" mass="0" density="0"/>
</default>
</default>
</default>

<asset>
<mesh name="z1_Link00" file="z1_Link00.stl"/>
<mesh name="z1_Link01" file="z1_Link01.stl"/>
<mesh name="z1_Link02" file="z1_Link02.stl"/>
<mesh name="z1_Link03" file="z1_Link03.stl"/>
<mesh name="z1_Link04" file="z1_Link04.stl"/>
<mesh name="z1_Link05" file="z1_Link05.stl"/>
<mesh name="z1_Link06" file="z1_Link06.stl"/>
<mesh file="z1_Link00.stl"/>
<mesh file="z1_Link01.stl"/>
<mesh file="z1_Link02.stl"/>
<mesh file="z1_Link03.stl"/>
<mesh file="z1_Link04.stl"/>
<mesh file="z1_Link05.stl"/>
<mesh file="z1_Link06.stl"/>
</asset>

<worldbody>
<body name="link00">
<body name="link00" childclass="z1">
<inertial pos="-0.00334984 -0.00013615 0.0249584" quat="-0.00692194 0.682592 0.00133293 0.730766" mass="0.472475"
diaginertia="0.000531375 0.000415207 0.000378658"/>
<geom class="visual" mesh="z1_Link00"/>
<geom size="0.0325 0.0255" pos="0 0 0.0255" class="collision"/>
<body name="link01" pos="0 0 0.0585">
<inertial pos="2.47e-06 -0.00025198 0.0231717" quat="0.708578 0.705633 0.000281462 -0.000355927" mass="0.673326"
diaginertia="0.00128328 0.000839362 0.000719308"/>
<joint name="joint1" pos="0 0 0" axis="0 0 1" range="-2.61799 2.61799" damping="1" frictionloss="1"/>
<joint name="joint1" axis="0 0 1" range="-2.61799 2.61799"/>
<geom class="visual" mesh="z1_Link01"/>
<body name="link02" pos="0 0 0.045">
<inertial pos="-0.110126 0.00240029 0.00158266" quat="0.00748058 0.707092 -0.0114473 0.70699" mass="1.19132"
diaginertia="0.0246612 0.0243113 0.00100468"/>
<joint name="joint2" pos="0 0 0" axis="0 1 0" range="0 2.96706" damping="2" frictionloss="2"/>
<joint name="joint2" axis="0 1 0" range="0 2.96706" damping="2"/>
<geom class="visual" mesh="z1_Link02"/>
<geom size="0.0325 0.051" quat="1 1 0 0" class="collision"/>
<geom size="0.0225 0.1175" pos="-0.1625 0 0" quat="1 0 1 0" class="collision"/>
<geom size="0.0325 0.0255" pos="-0.35 0 0" quat="1 1 0 0" class="collision"/>
<body name="link03" pos="-0.35 0 0">
<inertial pos="0.106092 -0.00541815 0.0347638" quat="0.540557 0.443575 0.426319 0.573839" mass="0.839409"
diaginertia="0.00954365 0.00938711 0.000558432"/>
<joint name="joint3" pos="0 0 0" axis="0 1 0" range="-2.87979 0" damping="1" frictionloss="1"/>
<joint name="joint3" axis="0 1 0" range="-2.87979 0"/>
<geom class="visual" mesh="z1_Link03"/>
<geom size="0.02 0.058" pos="0.128 0 0.055" quat="1 0 1 0" class="collision"/>
<geom size="0.0325 0.0295" pos="0.2205 0 0.055" quat="0.5 -0.5 0.5 0.5" class="collision"/>
<body name="link04" pos="0.218 0 0.057">
<inertial pos="0.0436668 0.00364738 -0.00170192" quat="0.0390835 0.726445 -0.0526787 0.684087"
mass="0.564046" diaginertia="0.000981656 0.00094053 0.000302655"/>
<joint name="joint4" pos="0 0 0" axis="0 1 0" range="-1.51844 1.51844" damping="1" frictionloss="1"/>
<joint name="joint4" axis="0 1 0" range="-1.51844 1.51844"/>
<geom class="visual" mesh="z1_Link04"/>
<geom size="0.0325 0.0335" pos="0.072 0 0" class="collision"/>
<body name="link05" pos="0.07 0 0">
<inertial pos="0.0312153 0 0.00646316" quat="0.462205 0.535209 0.53785 0.45895" mass="0.389385"
diaginertia="0.000558961 0.000547317 0.000167332"/>
<joint name="joint5" pos="0 0 0" axis="0 0 1" range="-1.3439 1.3439" damping="1" frictionloss="1"/>
<joint name="joint5" axis="0 0 1" range="-1.3439 1.3439"/>
<geom class="visual" mesh="z1_Link05"/>
<body name="link06" pos="0.0492 0 0">
<inertial pos="0.0241569 -0.00017355 -0.00143876" quat="0.998779 0.0457735 -0.00663717 0.0173548"
mass="0.288758" diaginertia="0.00018333 0.000147464 0.000146786"/>
<joint name="joint6" pos="0 0 0" axis="1 0 0" range="-2.79253 2.79253" damping="1" frictionloss="1"/>
<joint name="joint6" axis="1 0 0" range="-2.79253 2.79253"/>
<geom class="visual" mesh="z1_Link06"/>
<geom size="0.0325 0.0255" pos="0.0255 0 0" quat="1 0 1 0" class="collision"/>
</body>
</body>
</body>
Expand All @@ -64,11 +79,16 @@
</worldbody>

<actuator>
<general name="motor1" joint="joint1"/>
<general name="motor2" joint="joint2"/>
<general name="motor3" joint="joint3"/>
<general name="motor4" joint="joint4"/>
<general name="motor5" joint="joint5"/>
<general name="motor6" joint="joint6"/>
<general class="z1" name="motor1" joint="joint1" ctrlrange="-2.61799 2.61799"/>
<general class="z1" name="motor2" joint="joint2" ctrlrange="0 2.96706" forcerange="-60 60" gainprm="1500"
biasprm="0 -1500 -150"/>
<general class="z1" name="motor3" joint="joint3" ctrlrange="-2.87979 0"/>
<general class="z1" name="motor4" joint="joint4" ctrlrange="-1.51844 1.51844"/>
<general class="z1" name="motor5" joint="joint5" ctrlrange="-1.3439 1.3439"/>
<general class="z1" name="motor6" joint="joint6" ctrlrange="-2.79253 2.79253"/>
</actuator>

<keyframe>
<key name="home" qpos="0 0.785 -0.261 -0.523 0 0" ctrl="0 0.785 -0.261 -0.523 0 0"/>
</keyframe>
</mujoco>

0 comments on commit a099b54

Please sign in to comment.