unitree_ros/robots/laikago_description/urdf/laikago.urdf

542 lines
17 KiB
Plaintext
Raw Normal View History

2020-07-15 11:21:03 +08:00
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="laikago_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="silver">
<color rgba="0.913725490196 0.913725490196 0.847058823529 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/trunk.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.01675"/>
<geometry>
<box size="0.5616 0.172 0.1875"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.002284 -4.1e-05 0.025165"/>
<mass value="13.733"/>
<inertia ixx="0.073348887" ixy="0.00030338" ixz="0.001918218" iyy="0.250684593" iyz="-7.5402e-05" izz="0.254469458"/>
</inertial>
</link>
<joint name="FR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.21935 -0.0875 0"/>
<parent link="trunk"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-1.0471975512" upper="0.872664625997" velocity="52.4"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="3.14159265359 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.001568 0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="4.982e-06" ixz="-3.672e-05" iyy="0.000983196" iyz="-2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="FR_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.059 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="FR_thigh_shoulder">
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.08" radius="0.044"/>
</geometry>
</collision>
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.037 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="FR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 -0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="-1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="FR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
<joint name="FR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FR_calf"/>
<child link="FR_foot"/>
</joint>
<link name="FR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.21935 0.0875 0"/>
<parent link="trunk"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.872664625997" upper="1.0471975512" velocity="52.4"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.001568 -0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="-4.982e-06" ixz="-3.672e-05" iyy="0.000983196" iyz="2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="FL_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0.059 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="FL_thigh_shoulder">
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.08" radius="0.044"/>
</geometry>
</collision>
</link>
<joint name="FL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.037 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="FL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="-8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FL_thigh"/>
<child link="FL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="FL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
<joint name="FL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="FL_calf"/>
<child link="FL_foot"/>
</joint>
<link name="FL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
<joint name="RR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.21935 -0.0875 0"/>
<parent link="trunk"/>
<child link="RR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-1.0471975512" upper="0.872664625997" velocity="52.4"/>
</joint>
<link name="RR_hip">
<visual>
<origin rpy="3.14159265359 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.001568 0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="-4.982e-06" ixz="3.672e-05" iyy="0.000983196" iyz="-2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="RR_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.059 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="RR_thigh_shoulder">
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.08" radius="0.044"/>
</geometry>
</collision>
</link>
<joint name="RR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.037 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="RR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 -0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="-1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="RR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RR_thigh"/>
<child link="RR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="RR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
<joint name="RR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RR_calf"/>
<child link="RR_foot"/>
</joint>
<link name="RR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.21935 0.0875 0"/>
<parent link="trunk"/>
<child link="RL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="20" lower="-0.872664625997" upper="1.0471975512" velocity="52.4"/>
</joint>
<link name="RL_hip">
<visual>
<origin rpy="0 3.14159265359 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 -0.021 0"/>
<geometry>
<cylinder length="0.08" radius="0.041"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.001568 -0.008134 0.000864"/>
<mass value="1.096"/>
<inertia ixx="0.000822113" ixy="4.982e-06" ixz="3.672e-05" iyy="0.000983196" iyz="2.811e-06" izz="0.000864753"/>
</inertial>
</link>
<joint name="RL_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0.059 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="RL_thigh_shoulder">
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.08" radius="0.044"/>
</geometry>
</collision>
</link>
<joint name="RL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.037 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-0.523598775598" upper="3.92699081699" velocity="28.6"/>
</joint>
<link name="RL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/thigh.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.034 0.043"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000482 0.02001 -0.031996"/>
<mass value="1.528"/>
<inertia ixx="0.00991611" ixy="1.0388e-05" ixz="0.000250428" iyy="0.009280083" iyz="-8.511e-05" izz="0.00178256"/>
</inertial>
</link>
<joint name="RL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RL_thigh"/>
<child link="RL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="55" lower="-2.77507351067" upper="-0.610865238198" velocity="28.6"/>
</joint>
<link name="RL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../meshes/calf.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 1.57079632679 0" xyz="0 0 -0.125"/>
<geometry>
<box size="0.25 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.002196 -0.000381 -0.12338"/>
<mass value="0.241"/>
<inertia ixx="0.006181961" ixy="2.37e-07" ixz="-2.985e-06" iyy="0.006196546" iyz="5.138e-06" izz="3.4774e-05"/>
</inertial>
</link>
<joint name="RL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.25"/>
<parent link="RL_calf"/>
<child link="RL_foot"/>
</joint>
<link name="RL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0165"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0265"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="1.6854e-05" ixy="0.0" ixz="0.0" iyy="1.6854e-05" iyz="0.0" izz="1.6854e-05"/>
</inertial>
</link>
</robot>