| <?xml version="1.0" encoding="UTF-8"?> |
| <robot name="z1"> |
| <joint name="joint1" type="revolute"> |
| <origin xyz="0. 0. 0.0585" rpy="0. -1.5707964 0. "/> |
| <parent link="link00"/> |
| <child link="link01"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-2.6179936" upper="2.6179936" effort="30." velocity="3.1415"/> |
| </joint> |
| <joint name="joint2" type="revolute"> |
| <origin xyz="0.045 0. 0. " rpy="1.5707964 0. 1.5707964"/> |
| <parent link="link01"/> |
| <child link="link02"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="0." upper="2.9670595" effort="60." velocity="3.1415"/> |
| </joint> |
| <joint name="joint3" type="revolute"> |
| <origin xyz="0. 0.35 0. " rpy="0. 0. 0."/> |
| <parent link="link02"/> |
| <child link="link03"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-2.879793" upper="0." effort="30." velocity="3.1415"/> |
| </joint> |
| <joint name="joint4" type="revolute"> |
| <origin xyz="0. -0.218 0.057" rpy="0. 0. 0."/> |
| <parent link="link03"/> |
| <child link="link04"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-1.5184363" upper="1.5184363" effort="30." velocity="3.1415"/> |
| </joint> |
| <joint name="joint5" type="revolute"> |
| <origin xyz="0. -0.07 0. " rpy="-1.5707964 -1.5707964 0. "/> |
| <parent link="link04"/> |
| <child link="link05"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-1.3439035" upper="1.3439035" effort="30." velocity="3.1415"/> |
| </joint> |
| <joint name="joint6" type="revolute"> |
| <origin xyz="0. 0. -0.0492" rpy="0. 1.5707964 0. "/> |
| <parent link="link05"/> |
| <child link="link06"/> |
| <axis xyz="1. 0. 0."/> |
| <limit lower="-2.7925265" upper="2.7925265" effort="30." velocity="3.1415"/> |
| </joint> |
| <joint name="root_joint" type="fixed"> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <parent link="z1_description"/> |
| <child link="link00"/> |
| </joint> |
| <link name="link00"> |
| <inertial> |
| <origin xyz="-0.0033498 -0.0001362 0.0249584" rpy="0. 0. 0."/> |
| <mass value="0.4724748"/> |
| <inertia ixx="0.0003794" ixy="-0.0000004" ixz="-0.0000104" iyy="0.0004152" iyz="-0.000001" izz="0.0005307"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <geometry> |
| <mesh filename="meshes/link00_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0.0255" rpy="0. 0. 0."/> |
| <geometry> |
| <cylinder radius="0.0325" length="0.051"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="link01"> |
| <inertial> |
| <origin xyz="0.0000025 -0.000252 0.0231717" rpy="0. 0. 0."/> |
| <mass value="0.6733255"/> |
| <inertia ixx="0.0012833" ixy="-0.0000001" ixz="-0.0000004" iyy="0.0007193" iyz="0.0000005" izz="0.0008394"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/link01_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| </link> |
| <link name="link02"> |
| <inertial> |
| <origin xyz="-0.110126 0.0024003 0.0015827" rpy="0. 0. 0."/> |
| <mass value="1.1913226"/> |
| <inertia ixx="0.0010214" ixy="0.0006236" ixz="0.0000051" iyy="0.0242946" iyz="-0.0000021" izz="0.0246611"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. -1.5707964"/> |
| <geometry> |
| <mesh filename="meshes/link02_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. 0. 0." rpy="1.5707964 0. -1.5707964"/> |
| <geometry> |
| <cylinder radius="0.0325" length="0.102"/> |
| </geometry> |
| </collision> |
| <collision> |
| <origin xyz="0. 0.1625 0. " rpy="1.5707964 1.5707963 0. "/> |
| <geometry> |
| <cylinder radius="0.0225" length="0.235"/> |
| </geometry> |
| </collision> |
| <collision> |
| <origin xyz="0. 0.35 0. " rpy="1.5707964 0. -1.5707964"/> |
| <geometry> |
| <cylinder radius="0.0325" length="0.051"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="link03"> |
| <inertial> |
| <origin xyz="0.1060921 -0.0054182 0.0347638" rpy="0. 0. 0."/> |
| <mass value="0.8394088"/> |
| <inertia ixx="0.0010806" ixy="-0.0000867" ixz="-0.002081" iyy="0.0095424" iyz="-0.0000133" izz="0.0088662"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. -1.5707964"/> |
| <geometry> |
| <mesh filename="meshes/link03_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0. -0.128 0.055" rpy="1.5707964 1.5707963 0. "/> |
| <geometry> |
| <cylinder radius="0.02" length="0.116"/> |
| </geometry> |
| </collision> |
| <collision> |
| <origin xyz="0. -0.2205 0.055 " rpy="-0. 1.5707963 0. "/> |
| <geometry> |
| <cylinder radius="0.0325" length="0.059"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="link04"> |
| <inertial> |
| <origin xyz="0.0436668 0.0036474 -0.0017019" rpy="0. 0. 0."/> |
| <mass value="0.5640456"/> |
| <inertia ixx="0.0003158" ixy="0.0000813" ixz="0.0000409" iyy="0.00093" iyz="-0.000006" izz="0.0009791"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. -1.5707964"/> |
| <geometry> |
| <mesh filename="meshes/link04_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| </link> |
| <link name="link05"> |
| <inertial> |
| <origin xyz="0.0312153 0. 0.0064632" rpy="0. 0. 0."/> |
| <mass value="0.3893849"/> |
| <inertia ixx="0.0001761" ixy="0.0000004" ixz="0.0000569" iyy="0.000559" iyz="-0.0000001" izz="0.0005386"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 1.5707964 0. "/> |
| <geometry> |
| <mesh filename="meshes/link05_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| </link> |
| <link name="link06"> |
| <inertial> |
| <origin xyz="0.0241569 -0.0001735 -0.0014388" rpy="0. 0. 0."/> |
| <mass value="0.2887581"/> |
| <inertia ixx="0.0001833" ixy="0.0000012" ixz="0.0000005" iyy="0.0001475" iyz="0.0000001" izz="0.0001468"/> |
| </inertial> |
| <visual> |
| <origin xyz="0. 0. 0." rpy="0. 0. 0."/> |
| <geometry> |
| <mesh filename="meshes/link06_visuals_mesh_0.obj" scale="1. 1. 1."/> |
| </geometry> |
| </visual> |
| <collision> |
| <origin xyz="0.0255 0. 0. " rpy="0. 1.5707963 0. "/> |
| <geometry> |
| <cylinder radius="0.0325" length="0.051"/> |
| </geometry> |
| </collision> |
| </link> |
| <link name="z1_description"/> |
| </robot> |
|
|