unitree_ros/robots/z1_description/xacro/z1.urdf

277 lines
10 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="z1_description">
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/z1_gazebo</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo reference="link04">
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="link05">
<self_collide>true</self_collide>
</gazebo>
<gazebo reference="link06">
<self_collide>true</self_collide>
</gazebo>
<link name="world"/>
<joint name="base_static_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="link00"/>
</joint>
<link name="link00">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://z1_description/meshes/visual/z1_Link00.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="0.051" radius="0.0325"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0255"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00334984 -0.00013615 0.02495843"/>
<mass value="0.47247481"/>
<inertia ixx="0.00037937" ixy="-3.5e-07" ixz="-1.037e-05" iyy="0.00041521" iyz="-9.9e-07" izz="0.00053066"/>
</inertial>
</link>
<joint name="joint1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.0585"/>
<parent link="link00"/>
<child link="link01"/>
<axis xyz="0 0 1"/>
<dynamics damping="1.0" friction="1.0"/>
<limit effort="30.0" lower="-2.6179938779914944" upper="2.6179938779914944" velocity="3.1415"/>
</joint>
<link name="link01">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://z1_description/meshes/visual/z1_Link01.dae" scale="1 1 1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="2.47e-06 -0.00025198 0.02317169"/>
<mass value="0.67332551"/>
<inertia ixx="0.00128328" ixy="-6e-08" ixz="-4e-07" iyy="0.00071931" iyz="5e-07" izz="0.00083936"/>
</inertial>
</link>
<joint name="joint2" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.045"/>
<parent link="link01"/>
<child link="link02"/>
<axis xyz="0 1 0"/>
<dynamics damping="2.0" friction="2.0"/>
<limit effort="60.0" lower="0.0" upper="2.9670597283903604" velocity="3.1415"/>
</joint>
<link name="link02">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://z1_description/meshes/visual/z1_Link02.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="0.102" radius="0.0325"/>
</geometry>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
</collision>
<collision>
<geometry>
<cylinder length="0.235" radius="0.0225"/>
</geometry>
<origin rpy="0 1.5707963267948966 0" xyz="-0.16249999999999998 0 0"/>
</collision>
<collision>
<geometry>
<cylinder length="0.051" radius="0.0325"/>
</geometry>
<origin rpy="1.5707963267948966 0 0" xyz="-0.35 0 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.11012601 0.00240029 0.00158266"/>
<mass value="1.19132258"/>
<inertia ixx="0.00102138" ixy="0.00062358" ixz="5.13e-06" iyy="0.02429457" iyz="-2.1e-06" izz="0.02466114"/>
</inertial>
</link>
<joint name="joint3" type="revolute">
<origin rpy="0 0 0" xyz="-0.35 0 0"/>
<parent link="link02"/>
<child link="link03"/>
<axis xyz="0 1 0"/>
<dynamics damping="1.0" friction="1.0"/>
<limit effort="30.0" lower="-2.8797932657906435" upper="0.0" velocity="3.1415"/>
</joint>
<link name="link03">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://z1_description/meshes/visual/z1_Link03.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="0.116" radius="0.02"/>
</geometry>
<origin rpy="0 1.5707963267948966 0" xyz="0.128 0 0.055"/>
</collision>
<collision>
<geometry>
<cylinder length="0.059" radius="0.0325"/>
</geometry>
<origin rpy="0 1.5707963267948966 1.5707963267948966" xyz="0.2205 0 0.055"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.10609208 -0.00541815 0.03476383"/>
<mass value="0.83940874"/>
<inertia ixx="0.00108061" ixy="-8.669e-05" ixz="-0.00208102" iyy="0.00954238" iyz="-1.332e-05" izz="0.00886621"/>
</inertial>
</link>
<joint name="joint4" type="revolute">
<origin rpy="0 0 0" xyz="0.218 0 0.057"/>
<parent link="link03"/>
<child link="link04"/>
<axis xyz="0 1 0"/>
<dynamics damping="1.0" friction="1.0"/>
<limit effort="30.0" lower="-1.5184364492350666" upper="1.5184364492350666" velocity="3.1415"/>
</joint>
<link name="link04">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://z1_description/meshes/visual/z1_Link04.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="0.067" radius="0.0325"/>
</geometry>
<origin rpy="0 0 0" xyz="0.072 0 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.04366681 0.00364738 -0.00170192"/>
<mass value="0.56404563"/>
<inertia ixx="0.00031576" ixy="8.13e-05" ixz="4.091e-05" iyy="0.00092996" iyz="-5.96e-06" izz="0.00097912"/>
</inertial>
</link>
<joint name="joint5" type="revolute">
<origin rpy="0 0 0" xyz="0.07 0.0 0.0"/>
<parent link="link04"/>
<child link="link05"/>
<axis xyz="0 0 1"/>
<dynamics damping="1.0" friction="1.0"/>
<limit effort="30.0" lower="-1.3439035240356338" upper="1.3439035240356338" velocity="3.1415"/>
</joint>
<link name="link05">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://z1_description/meshes/visual/z1_Link05.dae" scale="1 1 1"/>
</geometry>
</visual>
<inertial>
<origin rpy="0 0 0" xyz="0.03121533 0.0 0.00646316"/>
<mass value="0.38938492"/>
<inertia ixx="0.00017605" ixy="4e-07" ixz="5.689e-05" iyy="0.00055896" iyz="-1.3e-07" izz="0.0005386"/>
</inertial>
</link>
<joint name="joint6" type="revolute">
<origin rpy="0 0 0" xyz="0.0492 0.0 0.0"/>
<parent link="link05"/>
<child link="link06"/>
<axis xyz="1 0 0"/>
<dynamics damping="1.0" friction="1.0"/>
<limit effort="30.0" lower="-2.792526803190927" upper="2.792526803190927" velocity="3.1415"/>
</joint>
<link name="link06">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://z1_description/meshes/visual/z1_Link06.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder length="0.051" radius="0.0325"/>
</geometry>
<origin rpy="0 1.5707963267948966 0" xyz="0.0255 0 0"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0241569 -0.00017355 -0.00143876"/>
<mass value="0.28875807"/>
<inertia ixx="0.00018328" ixy="1.22e-06" ixz="5.4e-07" iyy="0.0001475" iyz="8e-08" izz="0.0001468"/>
</inertial>
</link>
<transmission name="JointTrans1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="Actuator1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="JointTrans2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="Actuator2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="JointTrans3">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="Actuator3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="JointTrans4">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="Actuator4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="JointTrans5">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint5">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="Actuator5">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="JointTrans6">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint6">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="Actuator6">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>