diff --git a/robots/allegro_hand_description/urdf/allegro_left_hand.urdf b/robots/allegro_hand_description/urdf/allegro_left_hand.urdf
index ddcd10693b2a9d69cac2c75de8627bc5445fdecc..7d55683acc8fe0f10826ad80ed6d3731ff7b7732 100644
--- a/robots/allegro_hand_description/urdf/allegro_left_hand.urdf
+++ b/robots/allegro_hand_description/urdf/allegro_left_hand.urdf
@@ -4,33 +4,21 @@
 <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
 <!-- =================================================================================== -->
 <robot name="allegro_hand_left" xmlns:xacro="http://www.ros.org/wiki/xacro">
-  <!--
-rosrun xacro xacro.py allegro_hand_description_right.urdf.xacro > allegro_hand_description_right.urdf
-roslaunch launchers/fuerte/allegro_hand_jgui_right_virtual.launch
--->
   <!-- ======================== BASE PARAMS ========================= -->
   <!-- ======================== FINGER PARAMS ======================== -->
   <!-- full height from joint to tip. when used,
-the radius of the finger tip sphere will be subtracted
-and one fixed link will be added for the tip. -->
-  <!--0.0435,   0.044981-->
-  <!--0.002298-->
-  <!--0.002298-->
+         the radius of the finger tip sphere will be subtracted
+         and one fixed link will be added for the tip. -->
   <!-- ========================= THUMB PARAMS ========================= -->
   <!-- ========================= LIMITS ========================= -->
   <!-- ============================================================================= -->
-  <!-- ============================================================================= -->
-  <!-- ============================================================================= -->
-  <!-- BASE -->
-  <link name="base_link">
+  <!-- PALM -->
+  <link name="palm_link">
     <visual>
       <geometry>
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/base_link_left.STL"/>
       </geometry>
-      <!-- LEFT -->
       <origin rpy="-1.5707963259 0 0" xyz="0 0 0 "/>
-      <!-- RIGHT -->
-      <!--<origin rpy="0 0 0" xyz="0 0 0 "/>-->
       <material name="black">
         <color rgba="0.2 0.2 0.2 1"/>
       </material>
@@ -41,11 +29,17 @@ and one fixed link will be added for the tip. -->
         <box size="0.0408 0.1130 0.095"/>
       </geometry>
     </collision>
+    <inertial>
+      <origin rpy="0 0 0" xyz="0 0 0.0475"/>
+      <mass value="0.4154"/>
+      <inertia ixx="1e-4" ixy="0.0" ixz="0.0" iyy="1e-4" iyz="0.0" izz="1e-4"/>
+    </inertial>
   </link>
   <!-- ============================================================================= -->
   <!-- FINGERS -->
   <!-- RIGHT HAND due to which finger is number 0 -->
   <!-- for LEFT HAND switch the sign of the **offset_origin_y** and **finger_angle_r** parameters-->
+  <!-- [LINK 0, 4, 8] -->
   <link name="link_8.0">
     <visual>
       <geometry>
@@ -59,14 +53,21 @@ and one fixed link will be added for the tip. -->
       </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.01666658333e-06" ixy="0.0" ixz="0.0" iyy="6.47677333333e-07" iyz="0.0" izz="1.01666658333e-06"/>
+    </inertial>
   </link>
   <joint name="joint_8.0" type="revolute">
     <axis xyz="0 0 1"/>
-    <limit effort="0" lower="-0.47" upper="0.47" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="-0.47" upper="0.47" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_8.0"/>
     <origin rpy="-0.08726646255 0 0" xyz="0 0.0435 -0.001542"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 1, 5, 9] -->
   <link name="link_9.0">
     <visual>
       <geometry>
@@ -80,14 +81,21 @@ and one fixed link will be added for the tip. -->
       </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.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
+    </inertial>
   </link>
   <joint name="joint_9.0" type="revolute">
-    <limit effort="0" lower="-0.196" upper="1.61" velocity="0"/>
+    <limit effort="15" lower="-0.196" upper="1.61" velocity="7"/>
     <axis xyz="0 1 0"/>
     <parent link="link_8.0"/>
     <child link="link_9.0"/>
     <origin xyz="0 0 0.0164"/>
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 2, 6, 10]-->
   <link name="link_10.0">
     <visual>
       <geometry>
@@ -101,14 +109,21 @@ and one fixed link will be added for the tip. -->
       </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="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_10.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.174" upper="1.709" velocity="0"/>
+    <limit effort="15" lower="-0.174" upper="1.709" velocity="7"/>
     <parent link="link_9.0"/>
     <child link="link_10.0"/>
     <origin xyz="0 0 0.054"/>
+    <dynamics damping="8" friction="10"/>
   </joint>
+  <!-- [LINK 3, 7, 11] -->
   <link name="link_11.0">
     <visual>
       <geometry>
@@ -122,14 +137,21 @@ and one fixed link will be added for the tip. -->
       </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="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
+    </inertial>
   </link>
   <joint name="joint_11.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.227" upper="1.618" velocity="0"/>
+    <limit effort="15" lower="-0.227" upper="1.618" velocity="7"/>
     <parent link="link_10.0"/>
     <child link="link_11.0"/>
     <origin xyz="0 0 0.0384"/>
+    <dynamics damping="10" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_11.0_tip">
     <visual>
       <geometry>
@@ -144,12 +166,18 @@ and one fixed link will be added for the tip. -->
         <sphere radius="0.012"/>
       </geometry>
     </collision>
+    <inertial>
+      <mass value="0.0168"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </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.0267"/>
   </joint>
+  <!-- [LINK 0, 4, 8] -->
   <link name="link_4.0">
     <visual>
       <geometry>
@@ -163,14 +191,21 @@ and one fixed link will be added for the tip. -->
       </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.01666658333e-06" ixy="0.0" ixz="0.0" iyy="6.47677333333e-07" iyz="0.0" izz="1.01666658333e-06"/>
+    </inertial>
   </link>
   <joint name="joint_4.0" type="revolute">
     <axis xyz="0 0 1"/>
-    <limit effort="0" lower="-0.47" upper="0.47" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="-0.47" upper="0.47" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_4.0"/>
     <origin rpy="0.0 0 0" xyz="0 0 0.0007"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 1, 5, 9] -->
   <link name="link_5.0">
     <visual>
       <geometry>
@@ -184,14 +219,21 @@ and one fixed link will be added for the tip. -->
       </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.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
+    </inertial>
   </link>
   <joint name="joint_5.0" type="revolute">
-    <limit effort="0" lower="-0.196" upper="1.61" velocity="0"/>
+    <limit effort="15" lower="-0.196" upper="1.61" velocity="7"/>
     <axis xyz="0 1 0"/>
     <parent link="link_4.0"/>
     <child link="link_5.0"/>
     <origin xyz="0 0 0.0164"/>
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 2, 6, 10]-->
   <link name="link_6.0">
     <visual>
       <geometry>
@@ -205,14 +247,21 @@ and one fixed link will be added for the tip. -->
       </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="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_6.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.174" upper="1.709" velocity="0"/>
+    <limit effort="15" lower="-0.174" upper="1.709" velocity="7"/>
     <parent link="link_5.0"/>
     <child link="link_6.0"/>
     <origin xyz="0 0 0.054"/>
+    <dynamics damping="8" friction="10"/>
   </joint>
+  <!-- [LINK 3, 7, 11] -->
   <link name="link_7.0">
     <visual>
       <geometry>
@@ -226,14 +275,21 @@ and one fixed link will be added for the tip. -->
       </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="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
+    </inertial>
   </link>
   <joint name="joint_7.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.227" upper="1.618" velocity="0"/>
+    <limit effort="15" lower="-0.227" upper="1.618" velocity="7"/>
     <parent link="link_6.0"/>
     <child link="link_7.0"/>
     <origin xyz="0 0 0.0384"/>
+    <dynamics damping="10" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_7.0_tip">
     <visual>
       <geometry>
@@ -248,12 +304,18 @@ and one fixed link will be added for the tip. -->
         <sphere radius="0.012"/>
       </geometry>
     </collision>
+    <inertial>
+      <mass value="0.0168"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </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.0267"/>
   </joint>
+  <!-- [LINK 0, 4, 8] -->
   <link name="link_0.0">
     <visual>
       <geometry>
@@ -267,14 +329,21 @@ and one fixed link will be added for the tip. -->
       </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.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="0" lower="-0.47" upper="0.47" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="-0.47" upper="0.47" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_0.0"/>
     <origin rpy="0.08726646255 0 0" xyz="0 -0.0435 -0.001542"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 1, 5, 9] -->
   <link name="link_1.0">
     <visual>
       <geometry>
@@ -288,14 +357,21 @@ and one fixed link will be added for the tip. -->
       </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.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
+    </inertial>
   </link>
   <joint name="joint_1.0" type="revolute">
-    <limit effort="0" lower="-0.196" upper="1.61" velocity="0"/>
+    <limit effort="15" lower="-0.196" upper="1.61" velocity="7"/>
     <axis xyz="0 1 0"/>
     <parent link="link_0.0"/>
     <child link="link_1.0"/>
     <origin xyz="0 0 0.0164"/>
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 2, 6, 10]-->
   <link name="link_2.0">
     <visual>
       <geometry>
@@ -309,14 +385,21 @@ and one fixed link will be added for the tip. -->
       </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="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_2.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.174" upper="1.709" velocity="0"/>
+    <limit effort="15" lower="-0.174" upper="1.709" velocity="7"/>
     <parent link="link_1.0"/>
     <child link="link_2.0"/>
     <origin xyz="0 0 0.054"/>
+    <dynamics damping="8" friction="10"/>
   </joint>
+  <!-- [LINK 3, 7, 11] -->
   <link name="link_3.0">
     <visual>
       <geometry>
@@ -330,14 +413,21 @@ and one fixed link will be added for the tip. -->
       </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="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
+    </inertial>
   </link>
   <joint name="joint_3.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.227" upper="1.618" velocity="0"/>
+    <limit effort="15" lower="-0.227" upper="1.618" velocity="7"/>
     <parent link="link_2.0"/>
     <child link="link_3.0"/>
     <origin xyz="0 0 0.0384"/>
+    <dynamics damping="10" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_3.0_tip">
     <visual>
       <geometry>
@@ -352,6 +442,11 @@ and one fixed link will be added for the tip. -->
         <sphere radius="0.012"/>
       </geometry>
     </collision>
+    <inertial>
+      <mass value="0.0168"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </link>
   <joint name="joint_3.0_tip" type="fixed">
     <parent link="link_3.0"/>
@@ -359,30 +454,10 @@ and one fixed link will be added for the tip. -->
     <origin rpy="0 0 0" xyz="0 0 0.0267"/>
   </joint>
   <!-- THUMB -->
-  <!--
-<xacro:thumb_right
-	finger_num=			"3"
-	offset_origin_x=	"-0.0182"
-	offset_origin_y=	"0.019333"
-	offset_origin_z=	"-0.045987"
-
-
-	finger_angle_r=		"0"
-	finger_angle_p=		"-${95*DEG2RAD}"
-	finger_angle_y=		"-${90*DEG2RAD}"
-/>
--->
-  <!--
-	finger_angle_r=		"${90*DEG2RAD}"
-	finger_angle_p=		"-${100*DEG2RAD}"
-	finger_angle_y=		"${0*DEG2RAD}"
-	-->
+  <!-- [LINK 12] -->
   <link name="link_12.0">
     <visual>
       <geometry>
-        <!-- RIGHT -->
-        <!-- <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_12.0_right.STL" /> -->
-        <!-- LEFT -->
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_12.0_left.STL"/>
       </geometry>
       <material name="black">
@@ -394,19 +469,23 @@ and one fixed link will be added for the tip. -->
       <geometry>
         <box size="0.0358 0.034 0.0455"/>
       </geometry>
-      <!-- RIGHT -->
-      <!-- <origin rpy="0 0 0" xyz="${-0.0358/2+0.0} ${.018/2} ${.029/2}"/> -->
-      <!-- LEFT -->
       <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="1.89273333333e-5" ixy="7.16716e-06" ixz="5.35568e-06" iyy="1.43008213333e-05" iyz="6.8068e-06" izz="1.89273333333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_12.0" type="revolute">
     <axis xyz="+1 0 0"/>
-    <limit effort="0" lower="0.263" upper="1.396" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="0.263" upper="1.396" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_12.0"/>
     <origin rpy="0 -1.65806278845 1.5707963259" xyz="-0.0182 -0.019333 -0.045987"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 13] -->
   <link name="link_13.0">
     <visual>
       <geometry>
@@ -422,24 +501,28 @@ and one fixed link will be added for the tip. -->
       </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="4.24250866667e-06" ixy="1.032087e-06" ixz="1.603525e-06" iyy="4.52362633333e-06" iyz="1.44808125e-06" izz="4.24250866667e-06"/>
+    </inertial>
   </link>
   <joint name="joint_13.0" type="revolute">
     <axis xyz="0 0 -1"/>
-    <limit effort="0" lower="-0.105" upper="1.163" velocity="0"/>
+    <limit effort="15" lower="-0.105" upper="1.163" velocity="7"/>
     <parent link="link_12.0"/>
     <child link="link_13.0"/>
-    <!-- RIGHT -->
-    <!-- <origin xyz="-0.027 0.005 0.0399"/> -->
-    <!-- LEFT -->
     <origin xyz="-0.027 -0.005 0.0399"/>
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 14] -->
   <link name="link_14.0">
     <visual>
       <geometry>
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_14.0.STL"/>
       </geometry>
       <material name="black">
-		  	</material>
+                </material>
     </visual>
     <collision>
       <geometry>
@@ -447,21 +530,28 @@ and one fixed link will be added for the tip. -->
       </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="4.30439933333e-05" ixy="9.57068e-06" ixz="5.1205e-06" iyy="1.44451933333e-05" iyz="1.342825e-05" izz="4.30439933333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_14.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.189" upper="1.644" velocity="0"/>
+    <limit effort="15" lower="-0.189" upper="1.644" velocity="7"/>
     <parent link="link_13.0"/>
     <child link="link_14.0"/>
     <origin xyz="0 0 0.0177"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 15] -->
   <link name="link_15.0">
     <visual>
       <geometry>
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_15.0.STL"/>
       </geometry>
       <material name="black">
-    	</material>
+                </material>
     </visual>
     <collision>
       <geometry>
@@ -469,14 +559,21 @@ and one fixed link will be added for the tip. -->
       </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="3.29223173333e-05" ixy="8.042076e-06" ixz="5.2283e-06" iyy="1.47493026667e-5" iyz="1.1283525e-5" izz="3.29223173333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_15.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.162" upper="1.719" velocity="0"/>
+    <limit effort="15" lower="-0.162" upper="1.719" velocity="7"/>
     <parent link="link_14.0"/>
     <child link="link_15.0"/>
     <origin xyz="0 0 0.0514"/>
+    <dynamics damping="3" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_15.0_tip">
     <visual>
       <geometry>
@@ -492,16 +589,18 @@ and one fixed link will be added for the tip. -->
       </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="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </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.0423"/>
-    <!--0.0267000000000005-->
   </joint>
   <!-- ============================================================================= -->
-  <!-- ============================================================================= -->
-  <!-- ============================================================================= -->
   <!-- THUMB MACRO -->
   <!-- END THUMB MACRO -->
   <!-- THREE FINGER MACRO -->
diff --git a/robots/allegro_hand_description/urdf/allegro_right_hand.urdf b/robots/allegro_hand_description/urdf/allegro_right_hand.urdf
index c5d068d7c26d0a30d87d24deb243f7fa660e5817..5777cc92604d444830141240ef3bbb85cc398341 100644
--- a/robots/allegro_hand_description/urdf/allegro_right_hand.urdf
+++ b/robots/allegro_hand_description/urdf/allegro_right_hand.urdf
@@ -4,32 +4,20 @@
 <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
 <!-- =================================================================================== -->
 <robot name="allegro_hand_right" xmlns:xacro="http://www.ros.org/wiki/xacro">
-  <!--
-rosrun xacro xacro.py allegro_hand_description_right.urdf.xacro > allegro_hand_description_right.urdf
-roslaunch launchers/fuerte/allegro_hand_jgui_right_virtual.launch
--->
   <!-- ======================== BASE PARAMS ========================= -->
   <!-- ======================== FINGER PARAMS ======================== -->
   <!-- full height from joint to tip. when used,
-the radius of the finger tip sphere will be subtracted
-and one fixed link will be added for the tip. -->
-  <!--0.0435,   0.044981-->
-  <!--0.002298-->
-  <!--0.002298-->
+    the radius of the finger tip sphere will be subtracted
+    and one fixed link will be added for the tip. -->
   <!-- ========================= THUMB PARAMS ========================= -->
   <!-- ========================= LIMITS ========================= -->
   <!-- ============================================================================= -->
-  <!-- ============================================================================= -->
-  <!-- ============================================================================= -->
-  <!-- BASE -->
-  <link name="base_link">
+  <!-- PALM -->
+  <link name="palm_link">
     <visual>
       <geometry>
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/base_link.STL"/>
       </geometry>
-      <!-- LEFT -->
-      <!-- <origin rpy="${-90*DEG2RAD} 0 0" xyz="0 0 0 "/> -->
-      <!-- RIGHT -->
       <origin rpy="0 0 0" xyz="0 0 0 "/>
       <material name="black">
         <color rgba="0.2 0.2 0.2 1"/>
@@ -41,11 +29,17 @@ and one fixed link will be added for the tip. -->
         <box size="0.0408 0.1130 0.095"/>
       </geometry>
     </collision>
+    <inertial>
+      <origin rpy="0 0 0" xyz="0 0 0.0475"/>
+      <mass value="0.4154"/>
+      <inertia ixx="1e-4" ixy="0.0" ixz="0.0" iyy="1e-4" iyz="0.0" izz="1e-4"/>
+    </inertial>
   </link>
   <!-- ============================================================================= -->
   <!-- FINGERS -->
   <!-- RIGHT HAND due to which finger is number 0 -->
   <!-- for LEFT HAND switch the sign of the **offset_origin_y** and **finger_angle_r** parameters-->
+  <!-- [LINK 0, 4, 8] -->
   <link name="link_0.0">
     <visual>
       <geometry>
@@ -59,14 +53,21 @@ and one fixed link will be added for the tip. -->
       </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.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="0" lower="-0.47" upper="0.47" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="-0.47" upper="0.47" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_0.0"/>
     <origin rpy="-0.08726646255 0 0" xyz="0 0.0435 -0.001542"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 1, 5, 9] -->
   <link name="link_1.0">
     <visual>
       <geometry>
@@ -80,14 +81,21 @@ and one fixed link will be added for the tip. -->
       </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.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
+    </inertial>
   </link>
   <joint name="joint_1.0" type="revolute">
-    <limit effort="0" lower="-0.196" upper="1.61" velocity="0"/>
+    <limit effort="15" lower="-0.196" upper="1.61" velocity="7"/>
     <axis xyz="0 1 0"/>
     <parent link="link_0.0"/>
     <child link="link_1.0"/>
     <origin xyz="0 0 0.0164"/>
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 2, 6, 10]-->
   <link name="link_2.0">
     <visual>
       <geometry>
@@ -101,14 +109,21 @@ and one fixed link will be added for the tip. -->
       </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="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_2.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.174" upper="1.709" velocity="0"/>
+    <limit effort="15" lower="-0.174" upper="1.709" velocity="7"/>
     <parent link="link_1.0"/>
     <child link="link_2.0"/>
     <origin xyz="0 0 0.054"/>
+    <dynamics damping="8" friction="10"/>
   </joint>
+  <!-- [LINK 3, 7, 11] -->
   <link name="link_3.0">
     <visual>
       <geometry>
@@ -122,14 +137,21 @@ and one fixed link will be added for the tip. -->
       </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="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
+    </inertial>
   </link>
   <joint name="joint_3.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.227" upper="1.618" velocity="0"/>
+    <limit effort="15" lower="-0.227" upper="1.618" velocity="7"/>
     <parent link="link_2.0"/>
     <child link="link_3.0"/>
     <origin xyz="0 0 0.0384"/>
+    <dynamics damping="10" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_3.0_tip">
     <visual>
       <geometry>
@@ -144,12 +166,18 @@ and one fixed link will be added for the tip. -->
         <sphere radius="0.012"/>
       </geometry>
     </collision>
+    <inertial>
+      <mass value="0.0168"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </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.0267"/>
   </joint>
+  <!-- [LINK 0, 4, 8] -->
   <link name="link_4.0">
     <visual>
       <geometry>
@@ -163,14 +191,21 @@ and one fixed link will be added for the tip. -->
       </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.01666658333e-06" ixy="0.0" ixz="0.0" iyy="6.47677333333e-07" iyz="0.0" izz="1.01666658333e-06"/>
+    </inertial>
   </link>
   <joint name="joint_4.0" type="revolute">
     <axis xyz="0 0 1"/>
-    <limit effort="0" lower="-0.47" upper="0.47" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="-0.47" upper="0.47" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_4.0"/>
     <origin rpy="0.0 0 0" xyz="0 0 0.0007"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 1, 5, 9] -->
   <link name="link_5.0">
     <visual>
       <geometry>
@@ -184,14 +219,21 @@ and one fixed link will be added for the tip. -->
       </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.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
+    </inertial>
   </link>
   <joint name="joint_5.0" type="revolute">
-    <limit effort="0" lower="-0.196" upper="1.61" velocity="0"/>
+    <limit effort="15" lower="-0.196" upper="1.61" velocity="7"/>
     <axis xyz="0 1 0"/>
     <parent link="link_4.0"/>
     <child link="link_5.0"/>
     <origin xyz="0 0 0.0164"/>
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 2, 6, 10]-->
   <link name="link_6.0">
     <visual>
       <geometry>
@@ -205,14 +247,21 @@ and one fixed link will be added for the tip. -->
       </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="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_6.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.174" upper="1.709" velocity="0"/>
+    <limit effort="15" lower="-0.174" upper="1.709" velocity="7"/>
     <parent link="link_5.0"/>
     <child link="link_6.0"/>
     <origin xyz="0 0 0.054"/>
+    <dynamics damping="8" friction="10"/>
   </joint>
+  <!-- [LINK 3, 7, 11] -->
   <link name="link_7.0">
     <visual>
       <geometry>
@@ -226,14 +275,21 @@ and one fixed link will be added for the tip. -->
       </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="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
+    </inertial>
   </link>
   <joint name="joint_7.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.227" upper="1.618" velocity="0"/>
+    <limit effort="15" lower="-0.227" upper="1.618" velocity="7"/>
     <parent link="link_6.0"/>
     <child link="link_7.0"/>
     <origin xyz="0 0 0.0384"/>
+    <dynamics damping="10" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_7.0_tip">
     <visual>
       <geometry>
@@ -248,12 +304,18 @@ and one fixed link will be added for the tip. -->
         <sphere radius="0.012"/>
       </geometry>
     </collision>
+    <inertial>
+      <mass value="0.0168"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </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.0267"/>
   </joint>
+  <!-- [LINK 0, 4, 8] -->
   <link name="link_8.0">
     <visual>
       <geometry>
@@ -267,14 +329,21 @@ and one fixed link will be added for the tip. -->
       </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.01666658333e-06" ixy="0.0" ixz="0.0" iyy="6.47677333333e-07" iyz="0.0" izz="1.01666658333e-06"/>
+    </inertial>
   </link>
   <joint name="joint_8.0" type="revolute">
     <axis xyz="0 0 1"/>
-    <limit effort="0" lower="-0.47" upper="0.47" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="-0.47" upper="0.47" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_8.0"/>
     <origin rpy="0.08726646255 0 0" xyz="0 -0.0435 -0.001542"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 1, 5, 9] -->
   <link name="link_9.0">
     <visual>
       <geometry>
@@ -288,14 +357,21 @@ and one fixed link will be added for the tip. -->
       </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.95654166667e-05" ixy="1.7199e-05" ixz="8.75875e-06" iyy="2.47088833333e-05" iyz="2.413125e-05" izz="7.95654166667e-05"/>
+    </inertial>
   </link>
   <joint name="joint_9.0" type="revolute">
-    <limit effort="0" lower="-0.196" upper="1.61" velocity="0"/>
+    <limit effort="15" lower="-0.196" upper="1.61" velocity="7"/>
     <axis xyz="0 1 0"/>
     <parent link="link_8.0"/>
     <child link="link_9.0"/>
     <origin xyz="0 0 0.0164"/>
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 2, 6, 10]-->
   <link name="link_10.0">
     <visual>
       <geometry>
@@ -309,14 +385,21 @@ and one fixed link will be added for the tip. -->
       </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="2.63979183333e-05" ixy="6.67968e-06" ixz="4.783625e-06" iyy="1.34948516667e-05" iyz="9.372e-06" izz="2.63979183333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_10.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.174" upper="1.709" velocity="0"/>
+    <limit effort="15" lower="-0.174" upper="1.709" velocity="7"/>
     <parent link="link_9.0"/>
     <child link="link_10.0"/>
     <origin xyz="0 0 0.054"/>
+    <dynamics damping="8" friction="10"/>
   </joint>
+  <!-- [LINK 3, 7, 11] -->
   <link name="link_11.0">
     <visual>
       <geometry>
@@ -330,14 +413,21 @@ and one fixed link will be added for the tip. -->
       </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="4.701248e-06" ixy="1.255968e-06" ixz="1.2936e-06" iyy="3.649312e-06" iyz="1.7622e-06" izz="4.701248e-06"/>
+    </inertial>
   </link>
   <joint name="joint_11.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.227" upper="1.618" velocity="0"/>
+    <limit effort="15" lower="-0.227" upper="1.618" velocity="7"/>
     <parent link="link_10.0"/>
     <child link="link_11.0"/>
     <origin xyz="0 0 0.0384"/>
+    <dynamics damping="10" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_11.0_tip">
     <visual>
       <geometry>
@@ -352,6 +442,11 @@ and one fixed link will be added for the tip. -->
         <sphere radius="0.012"/>
       </geometry>
     </collision>
+    <inertial>
+      <mass value="0.0168"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </link>
   <joint name="joint_11.0_tip" type="fixed">
     <parent link="link_11.0"/>
@@ -359,35 +454,38 @@ and one fixed link will be added for the tip. -->
     <origin rpy="0 0 0" xyz="0 0 0.0267"/>
   </joint>
   <!-- THUMB -->
+  <!-- [LINK 12] -->
   <link name="link_12.0">
     <visual>
       <geometry>
-        <!-- RIGHT -->
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_12.0_right.STL"/>
-        <!-- LEFT -->
-        <!-- <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_12.0_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>
-      <!-- RIGHT -->
       <origin rpy="0 0 0" xyz="-0.0179 0.009 0.0145"/>
-      <!-- LEFT -->
-      <!-- <origin rpy="0 0 0" xyz="${-0.0358/2+0.0} ${-.018/2} ${.029/2}"/> -->
     </collision>
+    <inertial>
+      <mass value="0.0176"/>
+      <origin rpy="0 0 0" xyz="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>
   </link>
   <joint name="joint_12.0" type="revolute">
     <axis xyz="-1 0 0"/>
-    <limit effort="0" lower="0.263" upper="1.396" velocity="0"/>
-    <parent link="base_link"/>
+    <limit effort="15" lower="0.263" upper="1.396" velocity="7"/>
+    <parent link="palm_link"/>
     <child link="link_12.0"/>
     <origin rpy="0 -1.65806278845 -1.5707963259" xyz="-0.0182 0.019333 -0.045987"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 13] -->
   <link name="link_13.0">
     <visual>
       <geometry>
@@ -403,24 +501,28 @@ and one fixed link will be added for the tip. -->
       </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="4.24250866667e-06" ixy="1.032087e-06" ixz="1.603525e-06" iyy="4.52362633333e-06" iyz="1.44808125e-06" izz="4.24250866667e-06"/>
+    </inertial>
   </link>
   <joint name="joint_13.0" type="revolute">
     <axis xyz="0 0 1"/>
-    <limit effort="0" lower="-0.105" upper="1.163" velocity="0"/>
+    <limit effort="15" lower="-0.105" upper="1.163" velocity="7"/>
     <parent link="link_12.0"/>
     <child link="link_13.0"/>
-    <!-- RIGHT -->
     <origin xyz="-0.027 0.005 0.0399"/>
-    <!-- LEFT -->
-    <!-- <origin xyz="-0.027 -0.005 0.0399"/> -->
+    <dynamics damping="3" friction="5"/>
   </joint>
+  <!-- [LINK 14] -->
   <link name="link_14.0">
     <visual>
       <geometry>
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_14.0.STL"/>
       </geometry>
       <material name="black">
-		  	</material>
+                </material>
     </visual>
     <collision>
       <geometry>
@@ -428,21 +530,28 @@ and one fixed link will be added for the tip. -->
       </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="4.30439933333e-05" ixy="9.57068e-06" ixz="5.1205e-06" iyy="1.44451933333e-05" iyz="1.342825e-05" izz="4.30439933333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_14.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.189" upper="1.644" velocity="0"/>
+    <limit effort="15" lower="-0.189" upper="1.644" velocity="7"/>
     <parent link="link_13.0"/>
     <child link="link_14.0"/>
     <origin xyz="0 0 0.0177"/>
+    <dynamics damping="3" friction="10"/>
   </joint>
+  <!-- [LINK 15] -->
   <link name="link_15.0">
     <visual>
       <geometry>
         <mesh filename="package://example-robot-data/robots/allegro_hand_description/meshes/link_15.0.STL"/>
       </geometry>
       <material name="black">
-    	</material>
+                </material>
     </visual>
     <collision>
       <geometry>
@@ -450,14 +559,21 @@ and one fixed link will be added for the tip. -->
       </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="3.29223173333e-05" ixy="8.042076e-06" ixz="5.2283e-06" iyy="1.47493026667e-5" iyz="1.1283525e-5" izz="3.29223173333e-05"/>
+    </inertial>
   </link>
   <joint name="joint_15.0" type="revolute">
     <axis xyz="0 1 0"/>
-    <limit effort="0" lower="-0.162" upper="1.719" velocity="0"/>
+    <limit effort="15" lower="-0.162" upper="1.719" velocity="7"/>
     <parent link="link_14.0"/>
     <child link="link_15.0"/>
     <origin xyz="0 0 0.0514"/>
+    <dynamics damping="3" friction="12"/>
   </joint>
+  <!-- [FINGER TIP] -->
   <link name="link_15.0_tip">
     <visual>
       <geometry>
@@ -473,28 +589,17 @@ and one fixed link will be added for the tip. -->
       </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="9.68e-07" ixy="0" ixz="0" iyy="9.68e-07" iyz="0" izz="9.68e-07"/>
+    </inertial>
   </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.0423"/>
-    <!--0.0267000000000005-->
   </joint>
-  <!--
-<xacro:thumb_left
-	finger_num=			"3"
-	offset_origin_x=	"-0.0182"
-	offset_origin_y=	"-0.019333"
-	offset_origin_z=	"-0.045987"
-
-
-	finger_angle_r=		"${90*DEG2RAD}"
-	finger_angle_p=		"-${95*DEG2RAD}"
-	finger_angle_y=		"${90*DEG2RAD}"
-/>
--->
-  <!-- ============================================================================= -->
-  <!-- ============================================================================= -->
   <!-- ============================================================================= -->
   <!-- THUMB MACRO -->
   <!-- END THUMB MACRO -->