assets / allegro_hand /allegro_hand_right.urdf
yilingqqq's picture
add allegro hand (#5)
11e068c verified
<?xml version="1.0" encoding="utf-8"?>
<robot name="allegro_right">
<link name="base_link">
<inertial>
<mass value="0.4154"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="1e-4" ixy="0" ixz="0" iyy="1e-4" iyz="0" izz="1e-4"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/base_link.obj"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0 "/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.009 0.0 -0.023"/>
<geometry>
<box size="0.0414 0.112 0.0448"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-0.009 -0.0253 -0.0667"/>
<geometry>
<box size="0.0414 0.0538 0.0428"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="-0.009300 -0.00557 -0.08874"/>
<geometry>
<box size="0.0414 0.0720 0.013"/>
</geometry>
</collision>
</link> <!-- virtual link-->
<link name="palm"/>
<joint name="palm_joint" type="fixed">
<parent link="base_link"/>
<child link="palm"/>
<origin rpy="0.00000 -0.00000 0.00000" xyz="0 0 -0.065"/>
</joint> <!-- virtual link-->
<link name="wrist"/>
<joint name="wrist_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.03"/>
<parent link="palm"/>
<child link="wrist"/>
</joint>
<link name="link_0.0">
<visual>
<geometry>
<mesh filename="meshes/visual/link_0.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0164"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0082"/>
</collision>
<inertial>
<mass value="0.0119"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1.01666658333e-06" ixy="0.0" ixz="0.0" iyy="6.47677333333e-07" iyz="0.0" izz="1.01666658333e-06"/>
</inertial>
</link>
<joint name="joint_0.0" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10" lower="-0.47" upper="0.47" velocity="3.14"/>
<parent link="base_link"/>
<child link="link_0.0"/>
<origin rpy="-0.08726646255 0 0" xyz="0 0.0435 -0.001542"/>
</joint>
<link name="link_1.0">
<inertial>
<mass value="0.065"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="7.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_1.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.054"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.027"/>
</collision>
</link>
<joint name="joint_1.0" type="revolute">
<limit effort="10" lower="-0.196" upper="1.61" velocity="3.14"/>
<axis xyz="0 1 0"/>
<parent link="link_0.0"/>
<child link="link_1.0"/>
<origin xyz="0 0 0.0164"/>
</joint>
<link name="link_2.0">
<inertial>
<mass value="0.0355"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_2.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0384"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0192"/>
</collision>
</link>
<joint name="joint_2.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.174" upper="1.709" velocity="3.14"/>
<parent link="link_1.0"/>
<child link="link_2.0"/>
<origin xyz="0 0 0.054"/>
</joint>
<link name="link_3.0">
<visual>
<geometry>
<mesh filename="meshes/visual/link_3.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0269 0.022"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0047"/>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.01335"/>
<mass value="0.02"/>
<inertia ixx="1e-5" ixy="0.0" ixz="0.0" iyy="2e-5" iyz="0.0" izz="2e-5"/>
</inertial>
</link>
<joint name="joint_3.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.227" upper="1.618" velocity="3.14"/>
<parent link="link_2.0"/>
<child link="link_3.0"/>
<origin xyz="0 0 0.0384"/>
</joint>
<link name="link_3.0_tip">
<inertial>
<mass value="0.0168"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/visual/link_tip.obj"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/collision/link_tip.obj"/>
</geometry>
</collision>
</link>
<joint name="joint_3.0_tip" type="fixed">
<parent link="link_3.0"/>
<child link="link_3.0_tip"/>
<origin rpy="0 0 0" xyz="0 0 0.0387"/>
</joint>
<link name="link_4.0">
<inertial>
<mass value="0.005"/>
<origin xyz="0 0 0"/>
<inertia ixx="5.1458e-05" iyy="5.1458e-05" izz="6.125e-05" ixy="0" ixz="0" iyz="0"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_0.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0164"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0082"/>
</collision>
</link>
<joint name="joint_4.0" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10" lower="-0.47" upper="0.47" velocity="3.14"/>
<parent link="base_link"/>
<child link="link_4.0"/>
<origin rpy="0.0 0 0" xyz="0 0 0.0007"/>
</joint>
<link name="link_5.0">
<inertial>
<mass value="0.065"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="7.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_1.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.054"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.027"/>
</collision>
</link>
<joint name="joint_5.0" type="revolute">
<limit effort="10" lower="-0.196" upper="1.61" velocity="3.14"/>
<axis xyz="0 1 0"/>
<parent link="link_4.0"/>
<child link="link_5.0"/>
<origin xyz="0 0 0.0164"/>
</joint>
<link name="link_6.0">
<inertial>
<mass value="0.0355"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_2.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0384"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0192"/>
</collision>
</link>
<joint name="joint_6.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.174" upper="1.709" velocity="3.14"/>
<parent link="link_5.0"/>
<child link="link_6.0"/>
<origin xyz="0 0 0.054"/>
</joint>
<link name="link_7.0">
<inertial>
<mass value="0.0388"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="3.29223173333e-05" ixy="8.042076e-06" ixz="5.2283e-06" iyy="1.47493026667e-5" iyz="1.1283525e-5" izz="3.29223173333e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_3.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0269 0.022"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0047"/>
</collision>
</link>
<joint name="joint_7.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.227" upper="1.618" velocity="3.14"/>
<parent link="link_6.0"/>
<child link="link_7.0"/>
<origin xyz="0 0 0.0384"/>
</joint>
<link name="link_7.0_tip">
<inertial>
<mass value="0.0096"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/visual/link_tip.obj"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/collision/link_tip.obj"/>
</geometry>
</collision>
</link>
<joint name="joint_7.0_tip" type="fixed">
<parent link="link_7.0"/>
<child link="link_7.0_tip"/>
<origin rpy="0 0 0" xyz="0 0 0.0387"/>
</joint>
<link name="link_8.0">
<inertial>
<mass value="0.005"/>
<origin xyz="0 0 0"/>
<inertia ixx="5.1458e-05" iyy="5.1458e-05" izz="6.125e-05" ixy="0" ixz="0" iyz="0"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_0.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0164"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0082"/>
</collision>
</link>
<joint name="joint_8.0" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10" lower="-0.47" upper="0.47" velocity="3.14"/>
<parent link="base_link"/>
<child link="link_8.0"/>
<origin rpy="0.08726646255 0 0" xyz="0 -0.0435 -0.001542"/>
</joint>
<link name="link_9.0">
<inertial>
<mass value="0.065"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="7.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_1.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.054"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.027"/>
</collision>
</link>
<joint name="joint_9.0" type="revolute">
<limit effort="10" lower="-0.196" upper="1.61" velocity="3.14"/>
<axis xyz="0 1 0"/>
<parent link="link_8.0"/>
<child link="link_9.0"/>
<origin xyz="0 0 0.0164"/>
</joint>
<link name="link_10.0">
<inertial>
<mass value="0.0355"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_2.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0384"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0192"/>
</collision>
</link>
<joint name="joint_10.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.174" upper="1.709" velocity="3.14"/>
<parent link="link_9.0"/>
<child link="link_10.0"/>
<origin xyz="0 0 0.054"/>
</joint>
<link name="link_11.0">
<inertial>
<mass value="0.0096"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_3.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0269 0.022"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0047"/>
</collision>
</link>
<joint name="joint_11.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.227" upper="1.618" velocity="3.14"/>
<parent link="link_10.0"/>
<child link="link_11.0"/>
<origin xyz="0 0 0.0384"/>
</joint>
<link name="link_11.0_tip">
<inertial>
<mass value="0.0168"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/visual/link_tip.obj"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/collision/link_tip.obj"/>
</geometry>
</collision>
</link>
<joint name="joint_11.0_tip" type="fixed">
<parent link="link_11.0"/>
<child link="link_11.0_tip"/>
<origin rpy="0 0 0" xyz="0 0 0.0387"/>
</joint> <!-- THUMB -->
<link name="link_12.0">
<inertial>
<mass value="0.0176"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1.89273333333e-5" ixy="7.16716e-06" ixz="5.35568e-06" iyy="1.43008213333e-05" iyz="6.8068e-06" izz="1.89273333333e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_12.0_right.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0358 0.034 0.0455"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.0179 0.009 0.0145"/>
</collision>
</link>
<joint name="joint_12.0" type="revolute">
<axis xyz="-1 0 0"/>
<limit effort="10" lower="0.263" upper="1.396" velocity="3.14"/>
<parent link="base_link"/>
<child link="link_12.0"/>
<origin rpy="0 -1.65806278845 -1.5707963259" xyz="-0.0182 0.019333 -0.045987"/>
</joint>
<link name="link_13.0">
<inertial>
<mass value="0.0119"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="4.24250866667e-06" ixy="1.032087e-06" ixz="1.603525e-06" iyy="4.52362633333e-06" iyz="1.44808125e-06" izz="4.24250866667e-06"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_13.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0177"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.00885"/>
</collision>
</link>
<joint name="joint_13.0" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10" lower="-0.105" upper="1.163" velocity="3.14"/>
<parent link="link_12.0"/>
<child link="link_13.0"/>
<origin xyz="-0.027 0.005 0.0399"/>
</joint>
<link name="link_14.0">
<inertial>
<mass value="0.038"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="4.30439933333e-05" ixy="9.57068e-06" ixz="5.1205e-06" iyy="1.44451933333e-05" iyz="1.342825e-05" izz="4.30439933333e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_14.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0275 0.0514"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0257"/>
</collision>
</link>
<joint name="joint_14.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.189" upper="1.644" velocity="3.14"/>
<parent link="link_13.0"/>
<child link="link_14.0"/>
<origin xyz="0 0 0.0177"/>
</joint>
<link name="link_15.0">
<inertial>
<mass value="0.0388"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="3.29223173333e-05" ixy="8.042076e-06" ixz="5.2283e-06" iyy="1.47493026667e-5" iyz="1.1283525e-5" izz="3.29223173333e-05"/>
</inertial>
<visual>
<geometry>
<mesh filename="meshes/visual/link_15.0.obj"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.0196 0.0269 0.04"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.01125"/>
</collision>
</link>
<joint name="joint_15.0" type="revolute">
<axis xyz="0 1 0"/>
<limit effort="10" lower="-0.162" upper="1.719" velocity="3.14"/>
<parent link="link_14.0"/>
<child link="link_15.0"/>
<origin xyz="0 0 0.0514"/>
</joint>
<link name="link_15.0_tip">
<inertial>
<mass value="0.0168"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/visual/link_tip.obj"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.012"/>
<geometry>
<mesh filename="meshes/collision/link_tip.obj"/>
</geometry>
</collision>
</link>
<joint name="joint_15.0_tip" type="fixed">
<parent link="link_15.0"/>
<child link="link_15.0_tip"/>
<origin rpy="0 0 0" xyz="0 0 0.0543"/>
</joint>
</robot>