|
|
<?xml version="1.0" ?> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<robot name="allegro_hand_left" xmlns:xacro="http://www.ros.org/wiki/xacro"> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<link name="base_link"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/base_link_left.STL"/> |
|
|
</geometry> |
|
|
|
|
|
<origin rpy="-1.5707963259 0 0" xyz="0 0 0 "/> |
|
|
|
|
|
|
|
|
<material name="black"> |
|
|
<color rgba="0.2 0.2 0.2 1"/> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin rpy="0 0 0" xyz="-0.009300 0 -0.0475"/> |
|
|
<geometry> |
|
|
<box size="0.0408 0.1130 0.095"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<mass value="0.4154"/> |
|
|
<inertia ixx="2.089e-03" ixy="-0.0036e-03" ixz="0.2233e-03" iyy="1.829e-03" iyz="-0.018e-03" izz="0.4825e-03"/> |
|
|
</inertial> |
|
|
</link> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<link name="link_8"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_0.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</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 rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.95377e-06" ixy="3.03372e-09" ixz="8.92323e-08" iyy="1.17908e-06" iyz="-3.7069e-08" izz="1.49673e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_8" type="revolute"> |
|
|
<axis xyz="0 0 1"/> |
|
|
<limit effort="10.0" lower="-0.57" upper="0.57" velocity="3.0"/> |
|
|
<parent link="base_link"/> |
|
|
<child link="link_8"/> |
|
|
<origin rpy="-0.08726646255 0 0" xyz="0 0.0435 -0.001542"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_9"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_1.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.054"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.027"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.065"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="7.192e-05" ixy="0" ixz="0" iyy="7.438e-05" iyz="7.322e-07" izz="5.406e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_9" type="revolute"> |
|
|
<limit effort="10.0" lower="-0.296" upper="1.71" velocity="3.0"/> |
|
|
<axis xyz="0 1 0"/> |
|
|
<parent link="link_8"/> |
|
|
<child link="link_9"/> |
|
|
<origin xyz="0 0 0.0164"/> |
|
|
<dynamics damping="1.5e-2" friction="5"/> |
|
|
</joint> |
|
|
<link name="link_10"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_2.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0384"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0192"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0355"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="3.16925e-05" ixy="1.07094e-09" ixz="-4.91273e-09" iyy="3.10516e-05" iyz="3.87549e-08" izz="3.20319e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_10" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.274" upper="1.809" velocity="3.0"/> |
|
|
<parent link="link_9"/> |
|
|
<child link="link_10"/> |
|
|
<origin xyz="0 0 0.054"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_11"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_3.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0267"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.01335"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0096"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="2.13975e-06" ixy="1.59554e-09" ixz="-7.47528e-09" iyy="1.52036e-06" iyz="-9.89336e-09" izz="1.20271e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_11" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.327" upper="1.718" velocity="3.0"/> |
|
|
<parent link="link_10"/> |
|
|
<child link="link_11"/> |
|
|
<origin xyz="0 0 0.0384"/> |
|
|
<dynamics damping="1.5e-2" friction="12"/> |
|
|
</joint> |
|
|
<link name="link_11_tip"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_3_tip.STL"/> |
|
|
</geometry> |
|
|
<material name="white"> |
|
|
<color rgba=".9 .9 .9 1"/> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<sphere radius="0.012"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0168"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.19599e-05" ixy="0" ixz="0" iyy="1.19598e-05" iyz="0" izz="1.10345e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_11_tip" type="fixed"> |
|
|
<parent link="link_11"/> |
|
|
<child link="link_11_tip"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0267"/> |
|
|
</joint> |
|
|
<link name="link_4"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_0.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</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 rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.95377e-06" ixy="3.03372e-09" ixz="8.92323e-08" iyy="1.17908e-06" iyz="-3.7069e-08" izz="1.49673e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_4" type="revolute"> |
|
|
<axis xyz="0 0 1"/> |
|
|
<limit effort="10.0" lower="-0.57" upper="0.57" velocity="3.0"/> |
|
|
<parent link="base_link"/> |
|
|
<child link="link_4"/> |
|
|
<origin rpy="0.0 0 0" xyz="0 0 0.0007"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_5"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_1.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.054"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.027"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.065"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="7.19218e-05" ixy="0" ixz="0" iyy="7.4377e-05" iyz="7.32186e-07" izz="5.40622e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_5" type="revolute"> |
|
|
<limit effort="10.0" lower="-0.296" upper="1.71" velocity="3.0"/> |
|
|
<axis xyz="0 1 0"/> |
|
|
<parent link="link_4"/> |
|
|
<child link="link_5"/> |
|
|
<origin xyz="0 0 0.0164"/> |
|
|
<dynamics damping="1.5e-2" friction="5"/> |
|
|
</joint> |
|
|
<link name="link_6"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_2.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0384"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0192"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0355"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="3.16925e-05" ixy="1.07094e-09" ixz="-4.91273e-09" iyy="3.10516e-05" iyz="3.87549e-08" izz="3.20319e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_6" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.274" upper="1.809" velocity="3.0"/> |
|
|
<parent link="link_5"/> |
|
|
<child link="link_6"/> |
|
|
<origin xyz="0 0 0.054"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_7"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_3.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0267"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.01335"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0096"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="2.13975e-06" ixy="1.59554e-09" ixz="-7.47528e-09" iyy="1.52036e-06" iyz="-9.89336e-09" izz="1.20271e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_7" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.327" upper="1.718" velocity="3.0"/> |
|
|
<parent link="link_6"/> |
|
|
<child link="link_7"/> |
|
|
<origin xyz="0 0 0.0384"/> |
|
|
<dynamics damping="1.5e-2" friction="12"/> |
|
|
</joint> |
|
|
<link name="link_7_tip"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_3_tip.STL"/> |
|
|
</geometry> |
|
|
<material name="white"> |
|
|
<color rgba=".9 .9 .9 1"/> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<sphere radius="0.012"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0168"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.19599e-05" ixy="0" ixz="0" iyy="1.19598e-05" iyz="0" izz="1.10345e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_7_tip" type="fixed"> |
|
|
<parent link="link_7"/> |
|
|
<child link="link_7_tip"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0267"/> |
|
|
</joint> |
|
|
<link name="link_0"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_0.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</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 rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.95377e-06" ixy="3.03372e-09" ixz="8.92323e-08" iyy="1.17908e-06" iyz="-3.7069e-08" izz="1.49673e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_0" type="revolute"> |
|
|
<axis xyz="0 0 1"/> |
|
|
<limit effort="10.0" lower="-0.57" upper="0.57" velocity="3.0"/> |
|
|
<parent link="base_link"/> |
|
|
<child link="link_0"/> |
|
|
<origin rpy="0.08726646255 0 0" xyz="0 -0.0435 -0.001542"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_1"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_1.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.054"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.027"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.065"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="7.19218e-05" ixy="0" ixz="0" iyy="7.4377e-05" iyz="7.32186e-07" izz="5.40622e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_1" type="revolute"> |
|
|
<limit effort="10.0" lower="-0.296" upper="1.71" velocity="3.0"/> |
|
|
<axis xyz="0 1 0"/> |
|
|
<parent link="link_0"/> |
|
|
<child link="link_1"/> |
|
|
<origin xyz="0 0 0.0164"/> |
|
|
<dynamics damping="1.5e-2" friction="5"/> |
|
|
</joint> |
|
|
<link name="link_2"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_2.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0384"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0192"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0355"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="3.16925e-05" ixy="1.07094e-09" ixz="-4.91273e-09" iyy="3.10516e-05" iyz="3.87549e-08" izz="3.20319e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_2" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.274" upper="1.809" velocity="3.0"/> |
|
|
<parent link="link_1"/> |
|
|
<child link="link_2"/> |
|
|
<origin xyz="0 0 0.054"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_3"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_3.STL"/> |
|
|
</geometry> |
|
|
<material name="black"/> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0267"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.01335"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0096"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="2.13975e-06" ixy="1.59554e-09" ixz="-7.47528e-09" iyy="1.52036e-06" iyz="-9.89336e-09" izz="1.20271e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_3" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.327" upper="1.718" velocity="3.0"/> |
|
|
<parent link="link_2"/> |
|
|
<child link="link_3"/> |
|
|
<origin xyz="0 0 0.0384"/> |
|
|
<dynamics damping="1.5e-2" friction="12"/> |
|
|
</joint> |
|
|
<link name="link_3_tip"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_3_tip.STL"/> |
|
|
</geometry> |
|
|
<material name="white"> |
|
|
<color rgba=".9 .9 .9 1"/> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<sphere radius="0.012"/> |
|
|
</geometry> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0168"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.19599e-05" ixy="0" ixz="0" iyy="1.19598e-05" iyz="0" izz="1.10345e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_3_tip" type="fixed"> |
|
|
<parent link="link_3"/> |
|
|
<child link="link_3_tip"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0267"/> |
|
|
</joint> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<link name="link_12"> |
|
|
<visual> |
|
|
<geometry> |
|
|
|
|
|
|
|
|
|
|
|
<mesh filename="meshes/link_12_left.STL"/> |
|
|
</geometry> |
|
|
<material name="black"> |
|
|
<color rgba=".2 .2 .2 1"/> |
|
|
</material> |
|
|
<origin rpy="3.1415926518 0 0" xyz="0 0 0"/> |
|
|
</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> |
|
|
<inertial> |
|
|
<mass value="0.0176"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="8.13883e-06" ixy="-2.55226e-06" ixz="3.89933e-06" iyy="1.31421e-05" iyz="1.46267e-06" izz="1.00171e-05"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_12" type="revolute"> |
|
|
<axis xyz="+1 0 0"/> |
|
|
<limit effort="10.0" lower="0.363" upper="1.496" velocity="3.0"/> |
|
|
<parent link="base_link"/> |
|
|
<child link="link_12"/> |
|
|
<origin rpy="0 -1.65806278845 1.5707963259" xyz="-0.0182 -0.019333 -0.045987"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_13"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_13.STL"/> |
|
|
</geometry> |
|
|
<material name="black"> |
|
|
<color rgba=".2 .2 .2 1"/> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0177"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.00885"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0119"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.9263e-06" ixy="3.05433e-09" ixz="8.86582e-08" iyy="1.15276e-06" iyz="-3.64521e-08" izz="1.4957e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_13" type="revolute"> |
|
|
<axis xyz="0 0 -1"/> |
|
|
<limit effort="10.0" lower="-0.205" upper="1.163" velocity="3.0"/> |
|
|
<parent link="link_12"/> |
|
|
<child link="link_13"/> |
|
|
|
|
|
|
|
|
|
|
|
<origin xyz="-0.027 -0.005 0.0399"/> |
|
|
<dynamics damping="1.5e-2" friction="5"/> |
|
|
</joint> |
|
|
<link name="link_14"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_14.STL"/> |
|
|
</geometry> |
|
|
<material name="black"> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0514"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0257"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.038"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="3.67044e-05" ixy="1.02277e-09" ixz="1.4854e-07" iyy="3.54042e-05" iyz="-3.67203e-08" izz="3.63275e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_14" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.289" upper="1.644" velocity="3.0"/> |
|
|
<parent link="link_13"/> |
|
|
<child link="link_14"/> |
|
|
<origin xyz="0 0 0.0177"/> |
|
|
<dynamics damping="1.5e-2" friction="10"/> |
|
|
</joint> |
|
|
<link name="link_15"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_15.STL"/> |
|
|
</geometry> |
|
|
<material name="black"> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<box size="0.0196 0.0275 0.0423"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.02115"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0388"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="4.30919e-05" ixy="0" ixz="0" iyy="3.85425e-05" iyz="-3.0146e-08" izz="1.72974e-05"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_15" type="revolute"> |
|
|
<axis xyz="0 1 0"/> |
|
|
<limit effort="10.0" lower="-0.262" upper="1.819" velocity="3.0"/> |
|
|
<parent link="link_14"/> |
|
|
<child link="link_15"/> |
|
|
<origin xyz="0 0 0.0514"/> |
|
|
<dynamics damping="1.5e-2" friction="12"/> |
|
|
</joint> |
|
|
<link name="link_15_tip"> |
|
|
<visual> |
|
|
<geometry> |
|
|
<mesh filename="meshes/link_15_tip.STL"/> |
|
|
</geometry> |
|
|
<material name="white"> |
|
|
<color rgba=".9 .9 .9 1"/> |
|
|
</material> |
|
|
</visual> |
|
|
<collision> |
|
|
<geometry> |
|
|
<sphere radius="0.012"/> |
|
|
</geometry> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
</collision> |
|
|
<inertial> |
|
|
<mass value="0.0168"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0"/> |
|
|
<inertia ixx="1.19599e-05" ixy="0" ixz="0" iyy="1.19598e-05" iyz="0" izz="1.10345e-06"/> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="joint_15_tip" type="fixed"> |
|
|
<parent link="link_15"/> |
|
|
<child link="link_15_tip"/> |
|
|
<origin rpy="0 0 0" xyz="0 0 0.0423"/> |
|
|
|
|
|
</joint> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
</robot> |
|
|
|