quadruped_ros2_control/descriptions/unitree/go2_description/urdf/robot.urdf

521 lines
15 KiB
Plaintext
Raw Permalink Normal View History

2024-09-25 21:01:50 +08:00
<robot name="go2">
<material name="black">
<texture/>
<color rgba="0 0 0 1"/>
2024-09-25 21:01:50 +08:00
</material>
<material name="blue">
<texture/>
<color rgba="0 0 0.8 1"/>
</material>
<material name="brown">
<texture/>
<color rgba="0.870588 0.811765 0.764706 1"/>
2024-09-25 21:01:50 +08:00
</material>
<material name="green">
<texture/>
<color rgba="0 0.8 0 1"/>
2024-09-25 21:01:50 +08:00
</material>
<material name="grey">
<texture/>
<color rgba="0.2 0.2 0.2 0"/>
2024-09-25 21:01:50 +08:00
</material>
<material name="orange">
<texture/>
<color rgba="1 0.423529 0.0392157 1"/>
2024-09-25 21:01:50 +08:00
</material>
<material name="red">
<texture/>
<color rgba="0.8 0 0 1"/>
</material>
<material name="silver">
<texture/>
<color rgba="0.913725 0.913725 0.847059 1"/>
2024-09-25 21:01:50 +08:00
</material>
<material name="white">
<texture/>
<color rgba="1 1 1 1"/>
2024-09-25 21:01:50 +08:00
</material>
<link name="FL_calf">
<inertial>
<mass value="0.154"/>
<origin xyz="0.00548 -0.000975 -0.115" rpy="0 -0 0"/>
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
</inertial>
2024-09-25 21:01:50 +08:00
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.016 0.016"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<link name="FL_foot">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="0.06"/>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.01"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.02"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<link name="FL_hip">
<inertial>
<mass value="0.678"/>
<origin xyz="-0.0054 0.00194 -0.000105" rpy="0 -0 0"/>
<inertia ixx="0.00048" ixy="-3.01e-06" ixz="1.11e-06" iyy="0.000884" iyz="-1.42e-06" izz="0.000596"/>
</inertial>
2024-09-25 21:01:50 +08:00
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
2025-04-19 16:45:11 +08:00
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0.0955 0" rpy="1.5708 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<cylinder radius="0.046" length="0.04"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<link name="FL_thigh">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="1.152"/>
<origin xyz="-0.00374 -0.0223 -0.0327" rpy="0 -0 0"/>
<inertia ixx="0.00584" ixy="8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<mesh filename="../meshes/thigh.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<link name="FR_calf">
<inertial>
<mass value="0.154"/>
<origin xyz="0.00548 -0.000975 -0.115" rpy="0 -0 0"/>
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
</inertial>
2024-09-25 21:01:50 +08:00
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
2025-04-19 16:45:11 +08:00
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.016 0.016"/>
</geometry>
</collision>
</link>
<link name="FR_foot">
<inertial>
<mass value="0.06"/>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
2024-09-25 21:01:50 +08:00
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.01"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
</link>
<link name="FR_hip">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="0.678"/>
<origin xyz="-0.0054 -0.00194 -0.000105" rpy="0 -0 0"/>
<inertia ixx="0.00048" ixy="3.01e-06" ixz="1.11e-06" iyy="0.000884" iyz="1.42e-06" izz="0.000596"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="3.14159 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
2025-04-19 16:45:11 +08:00
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 -0.0955 0" rpy="1.5708 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<cylinder radius="0.046" length="0.04"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<link name="FR_thigh">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="1.152"/>
<origin xyz="-0.00374 0.0223 -0.0327" rpy="0 -0 0"/>
<inertia ixx="0.00584" ixy="-8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<mesh filename="../meshes/thigh_mirror.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<link name="RL_calf">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="0.154"/>
<origin xyz="0.00548 -0.000975 -0.115" rpy="0 -0 0"/>
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
2025-04-19 16:45:11 +08:00
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.016 0.016"/>
</geometry>
</collision>
</link>
<link name="RL_foot">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="0.06"/>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.01"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
</link>
<link name="RL_hip">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="0.678"/>
<origin xyz="0.0054 0.00194 -0.000105" rpy="0 -0 0"/>
<inertia ixx="0.00048" ixy="3.01e-06" ixz="-1.11e-06" iyy="0.000884" iyz="-1.42e-06" izz="0.000596"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="3.14159 1.22465e-16 3.14159"/>
2024-09-25 21:01:50 +08:00
<geometry>
2025-04-19 16:45:11 +08:00
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0.0955 0" rpy="1.5708 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<cylinder radius="0.046" length="0.04"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<link name="RL_thigh">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="1.152"/>
<origin xyz="-0.00374 -0.0223 -0.0327" rpy="0 -0 0"/>
<inertia ixx="0.00584" ixy="8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="0.000808" izz="0.00103"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<mesh filename="../meshes/thigh.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<link name="RR_calf">
<inertial>
<mass value="0.154"/>
<origin xyz="0.00548 -0.000975 -0.115" rpy="0 -0 0"/>
<inertia ixx="0.00108" ixy="3.4e-07" ixz="1.72e-05" iyy="0.0011" iyz="8.28e-06" izz="3.29e-05"/>
</inertial>
2024-09-25 21:01:50 +08:00
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
2025-04-19 16:45:11 +08:00
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.016 0.016"/>
</geometry>
</collision>
</link>
<link name="RR_foot">
<inertial>
<mass value="0.06"/>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertia ixx="9.6e-06" ixy="0" ixz="0" iyy="9.6e-06" iyz="0" izz="9.6e-06"/>
</inertial>
2024-09-25 21:01:50 +08:00
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.01"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
</link>
<link name="RR_hip">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="0.678"/>
<origin xyz="0.0054 -0.00194 -0.000105" rpy="0 -0 0"/>
<inertia ixx="0.00048" ixy="-3.01e-06" ixz="-1.11e-06" iyy="0.000884" iyz="1.42e-06" izz="0.000596"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="-1.22465e-16 1.22465e-16 3.14159"/>
2024-09-25 21:01:50 +08:00
<geometry>
2025-04-19 16:45:11 +08:00
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 -0.0955 0" rpy="1.5708 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<cylinder radius="0.046" length="0.04"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<link name="RR_thigh">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="1.152"/>
<origin xyz="-0.00374 0.0223 -0.0327" rpy="0 -0 0"/>
<inertia ixx="0.00584" ixy="-8.72e-05" ixz="-0.000289" iyy="0.0058" iyz="-0.000808" izz="0.00103"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<mesh filename="../meshes/thigh_mirror.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.1065" rpy="0 1.5708 -0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.213 0.0245 0.034"/>
</geometry>
</collision>
</link>
<link name="base">
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<link name="imu_link">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="0.001"/>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.001 0.001 0.001"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.001 0.001 0.001"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<link name="trunk">
2024-09-25 21:01:50 +08:00
<inertial>
<mass value="6.921"/>
<origin xyz="0.021112 0 -0.005366" rpy="0 -0 0"/>
<inertia ixx="0.02448" ixy="0.00012166" ixz="0.0014849" iyy="0.098077" iyz="-3.12e-05" izz="0.107"/>
2024-09-25 21:01:50 +08:00
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<mesh filename="../meshes/trunk.dae" scale="1 1 1"/>
2024-09-25 21:01:50 +08:00
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
2024-09-25 21:01:50 +08:00
<geometry>
<box size="0.3762 0.0935 0.114"/>
2024-09-25 21:01:50 +08:00
</geometry>
</collision>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="FL_thigh"/>
<child link="FL_calf"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.55" velocity="20.06" lower="-2.7227" upper="-0.83776"/>
</joint>
<joint name="FL_foot_fixed" type="fixed">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 0 0"/>
<parent link="FL_calf"/>
<child link="FL_foot"/>
</joint>
<joint name="FL_hip_joint" type="revolute">
<origin xyz="0.1934 0.0465 0" rpy="0 -0 0"/>
<axis xyz="1 0 0"/>
<parent link="trunk"/>
<child link="FL_hip"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.0472" upper="1.0472"/>
</joint>
<joint name="FL_thigh_joint" type="revolute">
<origin xyz="0 0.0955 0" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.5708" upper="3.4907"/>
</joint>
<joint name="FR_calf_joint" type="revolute">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.55" velocity="20.06" lower="-2.7227" upper="-0.83776"/>
</joint>
<joint name="FR_foot_fixed" type="fixed">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 0 0"/>
<parent link="FR_calf"/>
<child link="FR_foot"/>
</joint>
<joint name="FR_hip_joint" type="revolute">
<origin xyz="0.1934 -0.0465 0" rpy="0 -0 0"/>
<axis xyz="1 0 0"/>
<parent link="trunk"/>
<child link="FR_hip"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.0472" upper="1.0472"/>
</joint>
<joint name="FR_thigh_joint" type="revolute">
<origin xyz="0 -0.0955 0" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.5708" upper="3.4907"/>
</joint>
<joint name="RL_calf_joint" type="revolute">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="RL_thigh"/>
<child link="RL_calf"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.55" velocity="20.06" lower="-2.7227" upper="-0.83776"/>
</joint>
<joint name="RL_foot_fixed" type="fixed">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 0 0"/>
<parent link="RL_calf"/>
<child link="RL_foot"/>
</joint>
<joint name="RL_hip_joint" type="revolute">
<origin xyz="-0.1934 0.0465 0" rpy="0 -0 0"/>
<axis xyz="1 0 0"/>
<parent link="trunk"/>
<child link="RL_hip"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.0472" upper="1.0472"/>
</joint>
<joint name="RL_thigh_joint" type="revolute">
<origin xyz="0 0.0955 0" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.5708" upper="3.4907"/>
</joint>
<joint name="RR_calf_joint" type="revolute">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="RR_thigh"/>
<child link="RR_calf"/>
<dynamics damping="0" friction="0"/>
<limit effort="35.55" velocity="20.06" lower="-2.7227" upper="-0.83776"/>
</joint>
<joint name="RR_foot_fixed" type="fixed">
<origin xyz="0 0 -0.213" rpy="0 -0 0"/>
<axis xyz="0 0 0"/>
<parent link="RR_calf"/>
<child link="RR_foot"/>
</joint>
<joint name="RR_hip_joint" type="revolute">
<origin xyz="-0.1934 -0.0465 0" rpy="0 -0 0"/>
<axis xyz="1 0 0"/>
<parent link="trunk"/>
<child link="RR_hip"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.0472" upper="1.0472"/>
</joint>
<joint name="RR_thigh_joint" type="revolute">
<origin xyz="0 -0.0955 0" rpy="0 -0 0"/>
<axis xyz="0 1 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh"/>
<dynamics damping="0" friction="0"/>
<limit effort="23.7" velocity="30.1" lower="-1.5708" upper="3.4907"/>
</joint>
<joint name="floating_base" type="fixed">
<origin xyz="0 0 0" rpy="0 -0 0"/>
<axis xyz="0 0 0"/>
<parent link="base"/>
<child link="trunk"/>
</joint>
<joint name="imu_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 -0 0"/>
<axis xyz="0 0 0"/>
<parent link="trunk"/>
<child link="imu_link"/>
</joint>
2024-09-25 21:01:50 +08:00
</robot>