diff --git a/robots/kinova_description/robots/kinova.urdf b/robots/kinova_description/robots/kinova.urdf
index 5611306cdb15dbc84b2cb3bc81c2669a21c74029..2150d315f61352e4256c064081229f20e973e621 100644
--- a/robots/kinova_description/robots/kinova.urdf
+++ b/robots/kinova_description/robots/kinova.urdf
@@ -40,9 +40,21 @@
     <!-- Xacro:Properties -->
     <!-- [m] -->
     <!-- Base link -->
-    <link name="base"/>
+    <link name="base">
+      <inertial>
+        <mass value="0.0"/>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+      </inertial>
+    </link>
 
     <link name="jaco_front_hatch_support_v2">
+      <inertial>
+        <mass value="0.0"/>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+      </inertial>
+
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/kinova_description/meshes/jaco_front_hatch_support_v2.dae"/>
@@ -56,11 +68,17 @@
     </joint>
 
     <link name="jaco_mounting_block">
-        <visual>
-            <geometry>
-                <mesh filename="package://example-robot-data/robots/kinova_description/meshes/jaco_mounting_block.dae"/>
-            </geometry>
-        </visual>
+      <inertial>
+        <mass value="0.0"/>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+      </inertial>
+
+      <visual>
+        <geometry>
+          <mesh filename="package://example-robot-data/robots/kinova_description/meshes/jaco_mounting_block.dae"/>
+        </geometry>
+      </visual>
     </link>
     <joint name="jaco_support_to_jaco_mounting_block" type="fixed">
         <parent link="jaco_front_hatch_support_v2"/>
@@ -354,7 +372,13 @@
             <mechanicalReduction>160</mechanicalReduction>
         </actuator>
     </transmission>
-    <link name="j2s6s200_end_effector"/>
+    <link name="j2s6s200_end_effector">
+      <inertial>
+        <mass value="0.0"/>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+      </inertial>
+    </link>
     <joint name="j2s6s200_joint_end_effector" type="fixed">
         <parent link="j2s6s200_link_6"/>
         <child link="j2s6s200_end_effector"/>
diff --git a/robots/panda_description/urdf/panda.urdf b/robots/panda_description/urdf/panda.urdf
index cf01eec9097959e1c79dbb68a81ce09e29916dd3..c767772cdfd7f94de0fa241bde31844e0833456c 100644
--- a/robots/panda_description/urdf/panda.urdf
+++ b/robots/panda_description/urdf/panda.urdf
@@ -17,6 +17,11 @@
         </collision>
     </link>
     <link name="panda_link1">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link1.dae" />
@@ -37,6 +42,11 @@
         <limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.3925" />
     </joint>
     <link name="panda_link2">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link2.dae" />
@@ -57,6 +67,11 @@
         <limit effort="87" lower="-1.8326" upper="1.8326" velocity="2.3925" />
     </joint>
     <link name="panda_link3">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link3.dae" />
@@ -77,6 +92,11 @@
         <limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.3925" />
     </joint>
     <link name="panda_link4">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link4.dae" />
@@ -97,6 +117,11 @@
         <limit effort="87" lower="-3.1416" upper="0.0873" velocity="2.3925" />
     </joint>
     <link name="panda_link5">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link5.dae" />
@@ -117,6 +142,11 @@
         <limit effort="12" lower="-2.9671" upper="2.9671" velocity="2.8710" />
     </joint>
     <link name="panda_link6">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link6.dae" />
@@ -137,6 +167,11 @@
         <limit effort="12" lower="-0.0873" upper="3.8223" velocity="2.8710" />
     </joint>
     <link name="panda_link7">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/link7.dae" />
@@ -156,7 +191,13 @@
         <axis xyz="0 0 1" />
         <limit effort="12" lower="-2.9671" upper="2.9671" velocity="2.8710" />
     </joint>
-    <link name="panda_link8" />
+    <link name="panda_link8">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
+    </link>
     <joint name="panda_joint8" type="fixed">
         <origin rpy="0 0 0" xyz="0 0 0.107" />
         <parent link="panda_link7" />
@@ -169,6 +210,11 @@
         <origin rpy="0 0 -0.785398163397" xyz="0 0 0" />
     </joint>
     <link name="panda_hand">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/hand.dae" />
@@ -181,6 +227,11 @@
         </collision>
     </link>
     <link name="panda_leftfinger">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <geometry>
                 <mesh filename="package://example-robot-data/robots/panda_description/meshes/visual/finger.dae" />
@@ -193,6 +244,11 @@
         </collision>
     </link>
     <link name="panda_rightfinger">
+        <inertial>
+          <mass value="0"/>
+          <origin rpy="0 0 0" xyz="0 0 0"/>
+          <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+        </inertial>
         <visual>
             <origin rpy="0 0 3.14159265359" xyz="0 0 0" />
             <geometry>
diff --git a/robots/romeo_description/urdf/romeo.urdf b/robots/romeo_description/urdf/romeo.urdf
index bab144e94f1065c76240b8cea2bdafdffc36ab67..4a0bd75507e427a2e54ba1a831e151dd9a734933 100644
--- a/robots/romeo_description/urdf/romeo.urdf
+++ b/robots/romeo_description/urdf/romeo.urdf
@@ -87,7 +87,14 @@
     <child link="gaze"/>
     <origin rpy="0 0 0" xyz="0.11017 0 0.05426"/>
   </joint>
-  <link name="gaze"/>
+  <link name="gaze">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="LHipYaw" type="revolute">
     <parent link="body"/>
     <child link="LHipYawLink"/>
@@ -207,7 +214,14 @@
     <child link="l_sole"/>
     <origin rpy="0 0 0" xyz="0 0 -0.0684"/>
   </joint>
-  <link name="l_sole"/>
+  <link name="l_sole">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="RHipYaw" type="revolute">
     <parent link="body"/>
     <child link="RHipYawLink"/>
@@ -327,8 +341,22 @@
     <child link="r_sole"/>
     <origin rpy="0 0 0" xyz="0 0 -0.0684"/>
   </joint>
-  <link name="r_sole"/>
-  <link name="base_link"/>
+  <link name="r_sole">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
+  <link name="base_link">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="waist" type="fixed">
     <parent link="base_link"/>
     <child link="body"/>
@@ -671,121 +699,261 @@
       </geometry>
     </collision>
   </link>
-  <link name="ImuTorsoGyrometer_frame"/>
+  <link name="ImuTorsoGyrometer_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="ImuTorsoGyrometer_joint" type="fixed">
     <parent link="body"/>
     <child link="ImuTorsoGyrometer_frame"/>
     <origin rpy="0 0 0" xyz="0.06185 0.0087 -0.1582"/>
   </joint>
-  <link name="RFsrRCenter_frame"/>
+  <link name="RFsrRCenter_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="RFsrRCenter_joint" type="fixed">
     <parent link="r_ankle"/>
     <child link="RFsrRCenter_frame"/>
     <origin rpy="0 0 0" xyz="-0.04 0 -0.0646"/>
   </joint>
-  <link name="LFsrRCenter_frame"/>
+  <link name="LFsrRCenter_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="LFsrRCenter_joint" type="fixed">
     <parent link="l_ankle"/>
     <child link="LFsrRCenter_frame"/>
     <origin rpy="0 0 0" xyz="-0.04 0 -0.0646"/>
   </joint>
-  <link name="RFsrFR_frame"/>
+  <link name="RFsrFR_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+
   <joint name="RFsrFR_joint" type="fixed">
     <parent link="r_ankle"/>
     <child link="RFsrFR_frame"/>
     <origin rpy="0 0 0" xyz="0.13 -0.0337 -0.0646"/>
   </joint>
-  <link name="CameraLeftEye_frame"/>
+  <link name="CameraLeftEye_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="CameraLeftEye_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="CameraLeftEye_frame"/>
     <origin rpy="0 0 0" xyz="0.11017 0.03192 0.05426"/>
   </joint>
-  <link name="CameraRight_frame"/>
+  <link name="CameraRight_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="CameraRight_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="CameraRight_frame"/>
     <origin rpy="0 0 0" xyz="0.11999 -0.04 0.09938"/>
   </joint>
-  <link name="ImuHeadGyrometer_frame"/>
+  <link name="ImuHeadGyrometer_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="ImuHeadGyrometer_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="ImuHeadGyrometer_frame"/>
     <origin rpy="0 0 1.57079632679" xyz="-0.01135 -0.04225 0.16011"/>
   </joint>
-  <link name="ImuHeadAccelerometer_frame"/>
+  <link name="ImuHeadAccelerometer_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="ImuHeadAccelerometer_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="ImuHeadAccelerometer_frame"/>
     <origin rpy="0 0 1.57079632679" xyz="-0.01135 -0.04225 0.16011"/>
   </joint>
-  <link name="HeadTouchMiddle_frame"/>
+  <link name="HeadTouchMiddle_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+
   <joint name="HeadTouchMiddle_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="HeadTouchMiddle_frame"/>
     <origin rpy="0 -1.57079632679 0" xyz="0.001 0 0.1099"/>
   </joint>
-  <link name="CameraLeft_frame"/>
+  <link name="CameraLeft_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="CameraLeft_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="CameraLeft_frame"/>
     <origin rpy="0 0 0" xyz="0.11999 0.04 0.09938"/>
   </joint>
-  <link name="RFsrCenter_frame"/>
+  <link name="RFsrCenter_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="RFsrCenter_joint" type="fixed">
     <parent link="r_ankle"/>
     <child link="RFsrCenter_frame"/>
     <origin rpy="0 0 0" xyz="0.073 0.02 -0.0646"/>
   </joint>
-  <link name="LFsrCenter_frame"/>
+  <link name="LFsrCenter_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="LFsrCenter_joint" type="fixed">
     <parent link="l_ankle"/>
     <child link="LFsrCenter_frame"/>
     <origin rpy="0 0 0" xyz="0.073 0.02 -0.0646"/>
   </joint>
-  <link name="CameraDepth_frame"/>
+  <link name="CameraDepth_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="CameraDepth_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="CameraDepth_frame"/>
     <origin rpy="2.0043951 0 1.57079632679" xyz="0.1403 -0.04708 0.14655"/>
   </joint>
-  <link name="ImuTorsoAccelerometer_frame"/>
+  <link name="ImuTorsoAccelerometer_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="ImuTorsoAccelerometer_joint" type="fixed">
     <parent link="body"/>
     <child link="ImuTorsoAccelerometer_frame"/>
     <origin rpy="0 0 0" xyz="0.06185 0.0087 -0.1582"/>
   </joint>
-  <link name="RFsrFL_frame"/>
+  <link name="RFsrFL_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+
   <joint name="RFsrFL_joint" type="fixed">
     <parent link="r_ankle"/>
     <child link="RFsrFL_frame"/>
     <origin rpy="0 0 0" xyz="0.13 0.0337 -0.0646"/>
   </joint>
-  <link name="LFsrFL_frame"/>
+  <link name="LFsrFL_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="LFsrFL_joint" type="fixed">
     <parent link="l_ankle"/>
     <child link="LFsrFL_frame"/>
     <origin rpy="0 0 0" xyz="0.13 0.0337 -0.0646"/>
   </joint>
-  <link name="CameraRightEye_frame"/>
+  <link name="CameraRightEye_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="CameraRightEye_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="CameraRightEye_frame"/>
     <origin rpy="0 0 0" xyz="0.11017 -0.03192 0.05426"/>
   </joint>
-  <link name="HeadTouchFront_frame"/>
+  <link name="HeadTouchFront_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="HeadTouchFront_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="HeadTouchFront_frame"/>
     <origin rpy="0 -1.186099535 0" xyz="0.0312 0 0.1014"/>
   </joint>
-  <link name="LFsrFR_frame"/>
+  <link name="LFsrFR_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="LFsrFR_joint" type="fixed">
     <parent link="l_ankle"/>
     <child link="LFsrFR_frame"/>
     <origin rpy="0 0 0" xyz="0.13 -0.0337 -0.0646"/>
   </joint>
-  <link name="HeadTouchRear_frame"/>
+  <link name="HeadTouchRear_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+
   <joint name="HeadTouchRear_joint" type="fixed">
     <parent link="HeadRollLink"/>
     <child link="HeadTouchRear_frame"/>
@@ -796,13 +964,26 @@
     <child link="l_gripper"/>
     <origin rpy="-1.57079633 0 0" xyz="0.09 0 -0.02"/>
   </joint>
-  <link name="l_gripper"/>
+  <link name="l_gripper">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
   <joint name="r_gripper_joint" type="fixed">
     <parent link="r_wrist"/>
     <child link="r_gripper"/>
     <origin rpy="-1.57079633 0 0" xyz="0.09 0 -0.02"/>
   </joint>
-  <link name="r_gripper"/>
+  <link name="r_gripper">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <link name="LFinger11Link">
     <inertial>
       <origin rpy="0 0 0" xyz="0 0 0"/>
diff --git a/robots/talos_data/robots/talos_full_v2.urdf b/robots/talos_data/robots/talos_full_v2.urdf
index 42afc05a167215d6ea6e9de24b5ab9bfd9518471..245ee6abac5fdc945a96abca2501aff839902398 100644
--- a/robots/talos_data/robots/talos_full_v2.urdf
+++ b/robots/talos_data/robots/talos_full_v2.urdf
@@ -304,26 +304,50 @@
     <parent link="rgbd_link"/>
     <child link="rgbd_depth_frame"/>
   </joint>
-  <link name="rgbd_depth_frame"/>
+  <link name="rgbd_depth_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0.0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_depth_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_depth_frame"/>
     <child link="rgbd_depth_optical_frame"/>
   </joint>
-  <link name="rgbd_depth_optical_frame"/>
+  <link name="rgbd_depth_optical_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <!-- frames of the rgb sensor -->
   <joint name="rgbd_rgb_joint" type="fixed">
     <origin rpy="0 0 0" xyz="0.0 0.01251 0.0"/>
     <parent link="rgbd_link"/>
     <child link="rgbd_rgb_frame"/>
   </joint>
-  <link name="rgbd_rgb_frame"/>
+  <link name="rgbd_rgb_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_rgb_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_rgb_frame"/>
     <child link="rgbd_rgb_optical_frame"/>
   </joint>
-  <link name="rgbd_rgb_optical_frame"/>
+  <link name="rgbd_rgb_optical_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <gazebo reference="rgbd_link">
     <!-- IR + depth -->
     <sensor name="rgbd_frame_sensor" type="depth">
diff --git a/robots/talos_data/robots/talos_full_v2_box.urdf b/robots/talos_data/robots/talos_full_v2_box.urdf
index 7c90cadf4305f1f0dcebe4dc1d3b8bd9f261a6c8..c5a797bfc8812c5e3703f1564399cfa4ab95dc39 100644
--- a/robots/talos_data/robots/talos_full_v2_box.urdf
+++ b/robots/talos_data/robots/talos_full_v2_box.urdf
@@ -304,26 +304,50 @@
     <parent link="rgbd_link"/>
     <child link="rgbd_depth_frame"/>
   </joint>
-  <link name="rgbd_depth_frame"/>
+  <link name="rgbd_depth_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0.0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_depth_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_depth_frame"/>
     <child link="rgbd_depth_optical_frame"/>
   </joint>
-  <link name="rgbd_depth_optical_frame"/>
+  <link name="rgbd_depth_optical_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <!-- frames of the rgb sensor -->
   <joint name="rgbd_rgb_joint" type="fixed">
     <origin rpy="0 0 0" xyz="0.0 0.01251 0.0"/>
     <parent link="rgbd_link"/>
     <child link="rgbd_rgb_frame"/>
   </joint>
-  <link name="rgbd_rgb_frame"/>
+  <link name="rgbd_rgb_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_rgb_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_rgb_frame"/>
     <child link="rgbd_rgb_optical_frame"/>
   </joint>
-  <link name="rgbd_rgb_optical_frame"/>
+  <link name="rgbd_rgb_optical_frame">
+    <inertial>
+      <mass value="0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+    </inertial>
+  </link>
   <gazebo reference="rgbd_link">
     <!-- IR + depth -->
     <sensor name="rgbd_frame_sensor" type="depth">
diff --git a/robots/talos_data/robots/talos_reduced.urdf b/robots/talos_data/robots/talos_reduced.urdf
index ae5397381292be4f1dad94a9ae21150e79b80afc..d1f125dcbe686c28f21a7af3327edacaefabee98 100644
--- a/robots/talos_data/robots/talos_reduced.urdf
+++ b/robots/talos_data/robots/talos_reduced.urdf
@@ -289,17 +289,6 @@
       <!-- inertia tensor computed analytically for a solid cuboid -->
       <inertia ixx="0.000030" ixy="0.0" ixz="0.0" iyy="0.000030" iyz="0.0" izz="0.000002"/>
     </inertial>
-      <!--
-    <visual>
-      <origin rpy="0 0 0" xyz="0 0 0"/>
-	  <geometry>
-          <mesh filename="package://example-robot-data/robots/talos_data/meshes/sensors/orbbec/orbbec.STL"/>
-      </geometry>
-      <material name="DarkGrey">
-        <color rgba="0.5 0.5 0.5 1"/>
-      </material>
-    </visual>
-      -->
     <collision>
       <origin rpy="0 0 0" xyz="-0.01 0.0025 0"/>
       <geometry>
@@ -325,26 +314,50 @@
     <parent link="rgbd_link"/>
     <child link="rgbd_depth_frame"/>
   </joint>
-  <link name="rgbd_depth_frame"/>
+  <link name="rgbd_depth_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_depth_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_depth_frame"/>
     <child link="rgbd_depth_optical_frame"/>
   </joint>
-  <link name="rgbd_depth_optical_frame"/>
+  <link name="rgbd_depth_optical_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
   <!-- frames of the rgb sensor -->
   <joint name="rgbd_rgb_joint" type="fixed">
     <origin rpy="0 0 0" xyz="0.0 0.01251 0.0"/>
     <parent link="rgbd_link"/>
     <child link="rgbd_rgb_frame"/>
   </joint>
-  <link name="rgbd_rgb_frame"/>
+  <link name="rgbd_rgb_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_rgb_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_rgb_frame"/>
     <child link="rgbd_rgb_optical_frame"/>
   </joint>
-  <link name="rgbd_rgb_optical_frame"/>
+  <link name="rgbd_rgb_optical_frame" >
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
   <!-- extensions -->
   <gazebo reference="rgbd_link">
     <!-- IR + depth -->
@@ -449,7 +462,6 @@
     <!-- TODO: Missing reflects of inertias -->
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01346 0.0913 0.04812"/>
-      <!-- <mass value="1.52896"/> -->
       <mass value="1.42896"/>
       <inertia ixx="0.00555100000" ixy="-0.00073100000" ixz="0.00000800000" iyy="0.00167300000" iyz="-0.00006000000" izz="0.00582200000"/>
     </inertial>
@@ -482,7 +494,6 @@
   <link name="arm_left_2_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.02607 0.00049 -0.05209"/>
-      <!-- <mass value="1.77729"/> -->
       <mass value="1.67729"/>
       <inertia ixx="0.00708700000" ixy="-0.00001400000" ixz="0.00214200000" iyy="0.00793600000" iyz="0.00003000000" izz="0.00378800000"/>
     </inertial>
@@ -515,7 +526,6 @@
   <link name="arm_left_3_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.00841 0.01428 -0.22291"/>
-      <!-- <mass value="1.57029"/> -->
       <mass value="1.47029"/>
       <inertia ixx="0.00433200000" ixy="0.00015300000" ixz="-0.00049600000" iyy="0.00434000000" iyz="-0.00060900000" izz="0.00254300000"/>
     </inertial>
@@ -551,7 +561,6 @@
   <link name="arm_left_4_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00655 -0.02107 -0.02612"/>
-      <!-- <mass value="1.20216"/> -->
       <mass value="1.10216"/>
       <inertia ixx="0.00221700000" ixy="-0.00010100000" ixz="0.00028800000" iyy="0.00241800000" iyz="-0.00039300000" izz="0.00111500000"/>
     </inertial>
@@ -622,7 +631,6 @@
   <link name="arm_left_5_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00006 0.00326 0.07963"/>
-      <!-- <mass value="1.87792"/> -->
       <mass value="1.77792"/>
       <inertia ixx="0.00349500000" ixy="-0.00001300000" ixz="-0.00001000000" iyy="0.00436800000" iyz="0.00009700000" izz="0.00228300000"/>
     </inertial>
@@ -655,7 +663,6 @@
   <link name="arm_left_6_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.00002 -0.00197 -0.00059"/>
-      <!-- <mass value="0.40931"/> -->
       <mass value="0.30931"/>
       <inertia ixx="0.00010700000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00014100000" iyz="-0.00000000000" izz="0.00015400000"/>
     </inertial>
@@ -686,15 +693,6 @@
                           soft_upper_limit="${80.00000 * deg_to_rad - eps_radians}" /> -->
   </joint>
   <link name="arm_left_7_link">
-    <!-- WRONG VALUES
-      <inertial>
-        <origin xyz="-0.00089 0.00365 -0.07824" rpy="0.00000 0.00000 0.00000"/>
-        <mass value="1.02604"/>
-        <inertia ixx="0.00151400000" ixy="0.00000600000" ixz="0.00006600000"
-                 iyy="0.00146400000" iyz="0.00001200000"
-                 izz="0.00090300000"/>
-      </inertial>
-      -->
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.007525 0.001378 -0.024630"/>
       <mass value="0.308441"/>
@@ -833,7 +831,6 @@
     <!-- TODO: Missing reflects of inertias -->
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01346 -0.0913 0.04812"/>
-      <!-- <mass value="1.52896"/> -->
       <mass value="1.42896"/>
       <inertia ixx="0.00555100000" ixy="-0.00073100000" ixz="0.00000800000" iyy="0.00167300000" iyz="-0.00006000000" izz="0.00582200000"/>
     </inertial>
@@ -866,7 +863,6 @@
   <link name="arm_right_2_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.02607 0.00049 -0.05209"/>
-      <!-- <mass value="1.77729"/> -->
       <mass value="1.67729"/>
       <inertia ixx="0.00708700000" ixy="-0.00001400000" ixz="0.00214200000" iyy="0.00793600000" iyz="0.00003000000" izz="0.00378800000"/>
     </inertial>
@@ -899,7 +895,6 @@
   <link name="arm_right_3_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.00841 0.01428 -0.22291"/>
-      <!-- <mass value="1.57029"/> -->
       <mass value="1.47029"/>
       <inertia ixx="0.00433200000" ixy="0.00015300000" ixz="-0.00049600000" iyy="0.00434000000" iyz="-0.00060900000" izz="0.00254300000"/>
     </inertial>
@@ -935,7 +930,6 @@
   <link name="arm_right_4_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00655 -0.02107 -0.02612"/>
-      <!-- <mass value="1.20216"/> -->
       <mass value="1.10216"/>
       <inertia ixx="0.00221700000" ixy="-0.00010100000" ixz="0.00028800000" iyy="0.00241800000" iyz="-0.00039300000" izz="0.00111500000"/>
     </inertial>
@@ -1006,7 +1000,6 @@
   <link name="arm_right_5_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00006 0.00326 0.07963"/>
-      <!-- <mass value="1.87792"/> -->
       <mass value="1.77792"/>
       <inertia ixx="0.00349500000" ixy="-0.00001300000" ixz="-0.00001000000" iyy="0.00436800000" iyz="0.00009700000" izz="0.00228300000"/>
     </inertial>
@@ -1039,7 +1032,6 @@
   <link name="arm_right_6_link">
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.00002 -0.00197 -0.00059"/>
-      <!-- <mass value="0.40931"/> -->
       <mass value="0.30931"/>
       <inertia ixx="0.00010700000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00014100000" iyz="-0.00000000000" izz="0.00015400000"/>
     </inertial>
@@ -1070,15 +1062,6 @@
                           soft_upper_limit="${80.00000 * deg_to_rad - eps_radians}" /> -->
   </joint>
   <link name="arm_right_7_link">
-    <!-- WRONG VALUES
-      <inertial>
-        <origin xyz="-0.00089 0.00365 -0.07824" rpy="0.00000 0.00000 0.00000"/>
-        <mass value="1.02604"/>
-        <inertia ixx="0.00151400000" ixy="0.00000600000" ixz="0.00006600000"
-                 iyy="0.00146400000" iyz="0.00001200000"
-                 izz="0.00090300000"/>
-      </inertial>
-      -->
     <inertial>
       <origin rpy="0.00000 0.00000 0.00000" xyz="0.007525 0.001378 -0.024630"/>
       <mass value="0.308441"/>
diff --git a/robots/talos_data/robots/talos_reduced_box.urdf b/robots/talos_data/robots/talos_reduced_box.urdf
index 0a18b6f854c43f8d411ab855d93cd98a221fb2e1..e1baf716d662a62b19a782733924d96b76835204 100644
--- a/robots/talos_data/robots/talos_reduced_box.urdf
+++ b/robots/talos_data/robots/talos_reduced_box.urdf
@@ -325,26 +325,50 @@
     <parent link="rgbd_link"/>
     <child link="rgbd_depth_frame"/>
   </joint>
-  <link name="rgbd_depth_frame"/>
+  <link name="rgbd_depth_frame">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_depth_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_depth_frame"/>
     <child link="rgbd_depth_optical_frame"/>
   </joint>
-  <link name="rgbd_depth_optical_frame"/>
+  <link name="rgbd_depth_optical_frame">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
+  </link>
   <!-- frames of the rgb sensor -->
   <joint name="rgbd_rgb_joint" type="fixed">
     <origin rpy="0 0 0" xyz="0.0 0.01251 0.0"/>
     <parent link="rgbd_link"/>
     <child link="rgbd_rgb_frame"/>
   </joint>
-  <link name="rgbd_rgb_frame"/>
+  <link name="rgbd_rgb_frame">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
+  </link>
   <joint name="rgbd_rgb_optical_joint" type="fixed">
     <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
     <parent link="rgbd_rgb_frame"/>
     <child link="rgbd_rgb_optical_frame"/>
   </joint>
-  <link name="rgbd_rgb_optical_frame"/>
+  <link name="rgbd_rgb_optical_frame">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
+  </link>
   <!-- extensions -->
   <gazebo reference="rgbd_link">
     <!-- IR + depth -->
@@ -2193,8 +2217,8 @@
         <geometry>
           <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
         </geometry>
-      </collision> 
-      
+      </collision>
+
       -->
     <collision>
       <origin rpy="0 0 0" xyz="0 0 -0.1"/>
@@ -2519,8 +2543,8 @@
         <geometry>
           <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
         </geometry>
-      </collision> 
-      
+      </collision>
+
       -->
     <collision>
       <origin rpy="0 0 0" xyz="0 0 -0.1"/>
@@ -2786,4 +2810,3 @@
     <color rgba="1.0 0.5 0.0 1.0"/>
   </material>
 </robot>
-
diff --git a/robots/talos_data/robots/talos_reduced_corrected.urdf b/robots/talos_data/robots/talos_reduced_corrected.urdf
new file mode 100644
index 0000000000000000000000000000000000000000..8eb8e3643909890538dd998d8f20c37ae47ec409
--- /dev/null
+++ b/robots/talos_data/robots/talos_reduced_corrected.urdf
@@ -0,0 +1,2751 @@
+<?xml version="1.0" ?>
+<!-- =================================================================================== -->
+<!-- |    This document was autogenerated by xacro from talos_full.urdf.xacro          | -->
+<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
+<!-- =================================================================================== -->
+<!--
+
+  Copyright (c) 2016, PAL Robotics, S.L.
+  All rights reserved.
+
+  This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License.
+  To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to
+  Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA.
+-->
+<robot name="talos" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro">
+  <!--File includes-->
+  <!--Constant parameters-->
+  <!--File includes-->
+  <!-- Macro -->
+  <!--Constant parameters-->
+  <!--************************-->
+  <!--     HEAD_1 (TILT)      -->
+  <!--************************-->
+  <!--************************-->
+  <!--      HEAD_2 (PAN)      -->
+  <!--************************-->
+  <!--File includes-->
+  <!--File includes-->
+  <!--Constant parameters-->
+  <!--Constant parameters-->
+  <!--File includes-->
+  <!-- VIRTUAL (mimic) JOINTS -->
+  <!-- 0.45deg -->
+  <!--************************-->
+  <!--        TORSO_2  (TILT) -->
+  <!--************************-->
+  <link name="torso_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.04551 -0.00053 0.16386"/>
+      <mass value="17.55011"/>
+      <inertia ixx="0.37376900000" ixy="0.00063900000" ixz="0.01219600000" iyy="0.24790200000" iyz="0.00000700000" izz="0.28140400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/torso/torso_2.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/torso/torso_2_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <!--************************-->
+  <!--        TORSO_1  (PAN)  -->
+  <!--************************-->
+  <link name="torso_1_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00013 -0.00001 -0.01306"/>
+      <mass value="3.02433"/>
+      <inertia ixx="0.00759400000" ixy="0.00000100000" ixz="-0.00004800000" iyy="0.00429200000" iyz="-0.00000100000" izz="0.00749700000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/torso/torso_1.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/torso/torso_1.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="torso_1_joint" type="revolute">
+    <parent link="base_link"/>
+    <child link="torso_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0722"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="78.0" lower="-1.308996939" upper="1.308996939" velocity="5.4"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!-- <safety_controller k_position="20"
+                         k_velocity="20"
+                         soft_lower_limit="${-15.0 * deg_to_rad + torso_eps}"
+                         soft_upper_limit="${ 45.0 * deg_to_rad - torso_eps}" /> -->
+  </joint>
+  <!--************************-->
+  <!--        BASE_LINK       -->
+  <!--************************-->
+  <link name="base_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.08222 0.00838 -0.07261"/>
+      <mass value="13.53810"/>
+      <inertia ixx="0.06989000000" ixy="-0.00011700000" ixz="0.00023000000" iyy="0.03998200000" iyz="-0.00132500000" izz="0.08234500000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/torso/base_link.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/torso/base_link_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="torso_2_joint" type="revolute">
+    <parent link="torso_1_link"/>
+    <child link="torso_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="78.0" lower="-0.261799387799" upper="0.785398163397" velocity="5.4"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!-- <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-75.00000 * deg_to_rad + eps_radians}"
+                          soft_upper_limit="${75.00000 * deg_to_rad - eps_radians}" /> -->
+  </joint>
+  <link name="imu_link">
+    <inertial>
+      <mass value="0.01"/>
+      <origin xyz="0 0 0"/>
+      <inertia ixx="0.000001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.000001"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <box size="0.01 0.01 0.01"/>
+      </geometry>
+    </visual>
+  </link>
+  <joint name="imu_joint" type="fixed">
+    <origin rpy="3.14159265359 0 1.57079632679" xyz="0.04925 0 0.078"/>
+    <parent link="torso_2_link"/>
+    <child link="imu_link"/>
+  </joint>
+  <gazebo reference="torso_1_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="torso_2_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="base_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="torso_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="torso_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <!-- extensions -->
+  <transmission name="talos_torso_trans">
+    <type>transmission_interface/DifferentialTransmission</type>
+    <actuator name="torso_1_motor">
+      <role>actuator1</role>
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <actuator name="torso_2_motor">
+      <role>actuator2</role>
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="torso_1_joint">
+      <role>joint1</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>1.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+    <joint name="torso_2_joint">
+      <role>joint2</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>1.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <link name="head_1_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00120 0.00145 0.02165"/>
+      <mass value="0.65988"/>
+      <inertia ixx="0.00122100000" ixy="-0.00000400000" ixz="0.00007000000" iyy="0.00092400000" iyz="-0.00004100000" izz="0.00103300000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/head/head_1.stl" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/head/head_1_collision.stl" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="head_1_joint" type="revolute">
+    <parent link="torso_2_link"/>
+    <child link="head_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.31600"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="8.0" lower="-0.261799387799" upper="0.785398163397" velocity="1.0"/>
+    <dynamics damping="0.5" friction="1.0"/>
+    <!-- <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-15.00000 * deg_to_rad + eps_radians}"
+                          soft_upper_limit="${45.00000 * deg_to_rad - eps_radians}" /> -->
+  </joint>
+  <gazebo reference="head_1_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="head_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="head_1_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <link name="head_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01036 -0.00037 0.13778"/>
+      <mass value="1.40353"/>
+      <inertia ixx="0.00722500000" ixy="-0.00002500000" ixz="0.00032900000" iyy="0.00687300000" iyz="0.00004400000" izz="0.00437300000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/head/head_2.stl" scale="1 1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/head/head_2_collision.stl" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="head_2_joint" type="revolute">
+    <parent link="head_1_link"/>
+    <child link="head_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="4.0" lower="-1.308996939" upper="1.308996939" velocity="1.0"/>
+    <dynamics damping="0.5" friction="1.0"/>
+    <!-- <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-75.00000 * deg_to_rad + eps_radians}"
+                          soft_upper_limit="${75.00000 * deg_to_rad - eps_radians}" /> -->
+  </joint>
+  <gazebo reference="head_2_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="head_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="head_2_link">
+    <material>Gazebo/White</material>
+  </gazebo>
+  <!-- frames in the center of the camera -->
+  <joint name="rgbd_joint" type="fixed">
+    <origin rpy="0 0 0" xyz="0.066 0.0 0.1982"/>
+    <axis xyz="0 0 1"/>
+    <!-- <limit lower="0" upper="0.001" effort="100" velocity="0.01"/> -->
+    <parent link="head_2_link"/>
+    <child link="rgbd_link"/>
+  </joint>
+  <link name="rgbd_link">
+    <inertial>
+      <mass value="0.01"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <!-- inertia tensor computed analytically for a solid cuboid -->
+      <inertia ixx="0.000030" ixy="0.0" ixz="0.0" iyy="0.000030" iyz="0.0" izz="0.000002"/>
+    </inertial>
+    <collision>
+      <origin rpy="0 0 0" xyz="-0.01 0.0025 0"/>
+      <geometry>
+        <box size="0.04 0.185 0.03"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="rgbd_optical_joint" type="fixed">
+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
+    <parent link="rgbd_link"/>
+    <child link="rgbd_optical_frame"/>
+  </joint>
+  <link name="rgbd_optical_frame">
+    <inertial>
+      <mass value="0.01"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
+  <!-- frames of the depth sensor -->
+  <joint name="rgbd_depth_joint" type="fixed">
+    <origin rpy="0 0 0" xyz="0.0 0.03751 0.0"/>
+    <parent link="rgbd_link"/>
+    <child link="rgbd_depth_frame"/>
+  </joint>
+  <link name="rgbd_depth_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
+  <joint name="rgbd_depth_optical_joint" type="fixed">
+    <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
+    <parent link="rgbd_depth_frame"/>
+    <child link="rgbd_depth_optical_frame"/>
+  </joint>
+  <link name="rgbd_depth_optical_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
+  <!-- frames of the rgb sensor -->
+  <joint name="rgbd_rgb_joint" type="fixed">
+    <origin rpy="0 0 0" xyz="0.0 0.01251 0.0"/>
+    <parent link="rgbd_link"/>
+    <child link="rgbd_rgb_frame"/>
+  </joint>
+  <link name="rgbd_rgb_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
+  <joint name="rgbd_rgb_optical_joint" type="fixed">
+    <origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0 0 0"/>
+    <parent link="rgbd_rgb_frame"/>
+    <child link="rgbd_rgb_optical_frame"/>
+  </joint>
+  <link name="rgbd_rgb_optical_frame" >
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
+  <!-- extensions -->
+  <gazebo reference="rgbd_link">
+    <!-- IR + depth -->
+    <sensor name="rgbd_frame_sensor" type="depth">
+      <always_on>true</always_on>
+      <update_rate>6.0</update_rate>
+      <camera>
+        <horizontal_fov>1.01229096616</horizontal_fov>
+        <image>
+          <format>R8G8B8</format>
+          <width>320</width>
+          <height>240</height>
+        </image>
+        <clip>
+          <near>0.45</near>
+          <far>10.0</far>
+        </clip>
+      </camera>
+      <plugin filename="libgazebo_ros_openni_kinect.so" name="rgbd_frame_controller">
+        <alwaysOn>true</alwaysOn>
+        <updateRate>6.0</updateRate>
+        <cameraName>rgbd</cameraName>
+        <imageTopicName>ir/image_raw</imageTopicName>
+        <cameraInfoTopicName>ir/camera_info</cameraInfoTopicName>
+        <depthImageTopicName>depth/image_raw</depthImageTopicName>
+        <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
+        <pointCloudTopicName>depth/points</pointCloudTopicName>
+        <frameName>rgbd_optical_frame</frameName>
+        <pointCloudCutoff>0.45</pointCloudCutoff>
+        <rangeMax>10.0</rangeMax>
+        <distalostionK1>0.00000001</distalostionK1>
+        <distalostionK2>0.00000001</distalostionK2>
+        <distalostionK3>0.00000001</distalostionK3>
+        <distalostionT1>0.00000001</distalostionT1>
+        <distalostionT2>0.00000001</distalostionT2>
+      </plugin>
+    </sensor>
+    <!-- RGB -->
+    <sensor name="rgbd_frame_sensor" type="depth">
+      <always_on>true</always_on>
+      <update_rate>6.0</update_rate>
+      <camera>
+        <horizontal_fov>1.01229096616</horizontal_fov>
+        <image>
+          <format>R8G8B8</format>
+          <width>320</width>
+          <height>240</height>
+        </image>
+        <clip>
+          <near>0.45</near>
+          <far>10.0</far>
+        </clip>
+      </camera>
+      <plugin filename="libgazebo_ros_openni_kinect.so" name="rgbd_frame_controller">
+        <alwaysOn>true</alwaysOn>
+        <updateRate>6.0</updateRate>
+        <cameraName>rgbd</cameraName>
+        <imageTopicName>rgb/image_raw</imageTopicName>
+        <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
+        <pointCloudTopicName>rgb/points</pointCloudTopicName>
+        <frameName>rgbd_optical_frame</frameName>
+        <pointCloudCutoff>0.45</pointCloudCutoff>
+        <rangeMax>10.0</rangeMax>
+        <distalostionK1>0.00000001</distalostionK1>
+        <distalostionK2>0.00000001</distalostionK2>
+        <distalostionK3>0.00000001</distalostionK3>
+        <distalostionT1>0.00000001</distalostionT1>
+        <distalostionT2>0.00000001</distalostionT2>
+      </plugin>
+    </sensor>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <transmission name="talos_trans">
+    <type>transmission_interface/HalfDifferentialTransmission</type>
+    <actuator name="head_1_motor">
+      <role>actuator1</role>
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <actuator name="head_2_motor">
+      <role>actuator2</role>
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="head_1_joint">
+      <role>joint1</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>1.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+    <joint name="head_2_joint">
+      <role>joint2</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>2.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <!--************************-->
+  <!--        SHOULDER        -->
+  <!--************************-->
+  <link name="arm_left_1_link">
+    <!-- TODO: Missing reflects of inertias -->
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01346 0.0913 0.04812"/>
+      <mass value="1.42896"/>
+      <inertia ixx="0.00555100000" ixy="-0.00073100000" ixz="0.00000800000" iyy="0.00167300000" iyz="-0.00006000000" izz="0.00582200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_1_collision.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_1_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_left_1_joint" type="revolute">
+    <parent link="torso_2_link"/>
+    <child link="arm_left_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.1575 0.23200"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="44.64" lower="-1.57079632679" upper="0.523598775598" velocity="2.7"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--        <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-90.00000 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${30.00000 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <link name="arm_left_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02607 0.00049 -0.05209"/>
+      <mass value="1.67729"/>
+      <inertia ixx="0.00708700000" ixy="-0.00001400000" ixz="0.00214200000" iyy="0.00793600000" iyz="0.00003000000" izz="0.00378800000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_2_collision.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_2_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_left_2_joint" type="revolute">
+    <parent link="arm_left_1_link"/>
+    <child link="arm_left_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00493 0.1365 0.04673"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="22.32" lower="0.0" upper="2.87979326579" velocity="3.66"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--        <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${0.00000 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${165.00000 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <link name="arm_left_3_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00841 0.01428 -0.22291"/>
+      <mass value="1.47029"/>
+      <inertia ixx="0.00433200000" ixy="0.00015300000" ixz="-0.00049600000" iyy="0.00434000000" iyz="-0.00060900000" izz="0.00254300000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_3_collision.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_3_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_left_3_joint" type="revolute">
+    <parent link="arm_left_2_link"/>
+    <child link="arm_left_3_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="17.86" lower="-2.44346095279" upper="2.44346095279" velocity="4.58"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-140.0 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${140.0 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <!--************************-->
+  <!--        ELBOW           -->
+  <!--************************-->
+  <link name="arm_left_4_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00655 -0.02107 -0.02612"/>
+      <mass value="1.10216"/>
+      <inertia ixx="0.00221700000" ixy="-0.00010100000" ixz="0.00028800000" iyy="0.00241800000" iyz="-0.00039300000" izz="0.00111500000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_4_collision.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_4_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_left_4_joint" type="revolute">
+    <parent link="arm_left_3_link"/>
+    <child link="arm_left_4_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.02000 0.00000 -0.27300"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="17.86" lower="-2.35619449019" upper="0.0" velocity="4.58"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-135.0 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${0.0 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <gazebo reference="arm_left_1_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_left_2_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_left_3_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_left_4_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_left_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_left_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_left_3_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_left_4_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <!--************************-->
+  <!--        WRIST           -->
+  <!--************************-->
+  <!--************************-->
+  <!--        WRIST           -->
+  <!--************************-->
+  <link name="arm_left_5_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00006 0.00326 0.07963"/>
+      <mass value="1.77792"/>
+      <inertia ixx="0.00349500000" ixy="-0.00001300000" ixz="-0.00001000000" iyy="0.00436800000" iyz="0.00009700000" izz="0.00228300000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_5_collision.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_5_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_left_5_joint" type="revolute">
+    <parent link="arm_left_4_link"/>
+    <child link="arm_left_5_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="-0.02000 0.00000 -0.26430"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="3" lower="-2.53072741539" upper="2.53072741539" velocity="1.95"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-145.00000 * deg_to_rad + wrist_eps}"
+                          soft_upper_limit="${145.00000 * deg_to_rad - wrist_eps}" /> -->
+  </joint>
+  <link name="arm_left_6_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00002 -0.00197 -0.00059"/>
+      <mass value="0.30931"/>
+      <inertia ixx="0.00010700000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00014100000" iyz="-0.00000000000" izz="0.00015400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_6_collision.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_6_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_left_6_joint" type="revolute">
+    <parent link="arm_left_5_link"/>
+    <child link="arm_left_6_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="6.6" lower="-1.3962634016" upper="1.3962634016" velocity="1.76"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-80.00000 * deg_to_rad + eps_radians}"
+                          soft_upper_limit="${80.00000 * deg_to_rad - eps_radians}" /> -->
+  </joint>
+  <link name="arm_left_7_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.007525 0.001378 -0.024630"/>
+      <mass value="0.308441"/>
+      <inertia ixx="0.000309" ixy="0.000002" ixz="-0.000002" iyy="0.000219" iyz="0.000012" izz="0.000176"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_7.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_7_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_left_7_joint" type="revolute">
+    <parent link="arm_left_6_link"/>
+    <child link="arm_left_7_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="6.6" lower="-0.698131700798" upper="0.698131700798" velocity="1.76"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-40.00000 * deg_to_rad + eps_radians}"
+                          soft_upper_limit="${40.00000 * deg_to_rad - eps_radians}" /> -->
+  </joint>
+  <gazebo reference="arm_left_5_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="arm_left_6_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="arm_left_7_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_left_5_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_left_6_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_left_7_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <!-- extensions -->
+  <transmission name="arm_left_5_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_left_5_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_left_5_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="wrist_left_trans">
+    <type>transmission_interface/DifferentialTransmission</type>
+    <actuator name="arm_left_6_motor">
+      <role>actuator1</role>
+      <mechanicalReduction>-1.0</mechanicalReduction>
+    </actuator>
+    <actuator name="arm_left_7_motor">
+      <role>actuator2</role>
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_left_6_joint">
+      <role>joint1</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>-1.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+    <joint name="arm_left_7_joint">
+      <role>joint2</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>-1.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <!-- extensions -->
+  <transmission name="arm_left_1_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_left_1_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_left_1_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="arm_left_2_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_left_2_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_left_2_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="arm_left_3_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_left_3_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_left_3_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="arm_left_4_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_left_4_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_left_4_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <!--************************-->
+  <!--        SHOULDER        -->
+  <!--************************-->
+  <link name="arm_right_1_link">
+    <!-- TODO: Missing reflects of inertias -->
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01346 -0.0913 0.04812"/>
+      <mass value="1.42896"/>
+      <inertia ixx="0.00555100000" ixy="-0.00073100000" ixz="0.00000800000" iyy="0.00167300000" iyz="-0.00006000000" izz="0.00582200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_1_collision.STL" scale="1 -1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_1_collision.STL" scale="1 -1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_right_1_joint" type="revolute">
+    <parent link="torso_2_link"/>
+    <child link="arm_right_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.1575 0.23200"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="44.64" lower="-0.523598775598" upper="1.57079632679" velocity="2.7"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--        <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-90.00000 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${30.00000 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <link name="arm_right_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02607 0.00049 -0.05209"/>
+      <mass value="1.67729"/>
+      <inertia ixx="0.00708700000" ixy="-0.00001400000" ixz="0.00214200000" iyy="0.00793600000" iyz="0.00003000000" izz="0.00378800000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_2_collision.STL" scale="1 -1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_2_collision.STL" scale="1 -1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_right_2_joint" type="revolute">
+    <parent link="arm_right_1_link"/>
+    <child link="arm_right_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00493 -0.1365 0.04673"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="22.32" lower="-2.87979326579" upper="0.0" velocity="3.66"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--        <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${0.00000 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${165.00000 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <link name="arm_right_3_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00841 0.01428 -0.22291"/>
+      <mass value="1.47029"/>
+      <inertia ixx="0.00433200000" ixy="0.00015300000" ixz="-0.00049600000" iyy="0.00434000000" iyz="-0.00060900000" izz="0.00254300000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_3_collision.STL" scale="1 -1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_3_collision.STL" scale="1 -1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_right_3_joint" type="revolute">
+    <parent link="arm_right_2_link"/>
+    <child link="arm_right_3_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="17.86" lower="-2.44346095279" upper="2.44346095279" velocity="4.58"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-140.0 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${140.0 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <!--************************-->
+  <!--        ELBOW           -->
+  <!--************************-->
+  <link name="arm_right_4_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00655 -0.02107 -0.02612"/>
+      <mass value="1.10216"/>
+      <inertia ixx="0.00221700000" ixy="-0.00010100000" ixz="0.00028800000" iyy="0.00241800000" iyz="-0.00039300000" izz="0.00111500000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_4_collision.STL" scale="1 -1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_4_collision.STL" scale="1 -1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_right_4_joint" type="revolute">
+    <parent link="arm_right_3_link"/>
+    <child link="arm_right_4_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.02000 0.00000 -0.27300"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="17.86" lower="-2.35619449019" upper="0.0" velocity="4.58"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-135.0 * deg_to_rad + arm_eps}"
+                          soft_upper_limit="${0.0 * deg_to_rad - arm_eps}" /> -->
+  </joint>
+  <gazebo reference="arm_right_1_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_right_2_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_right_3_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_right_4_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_right_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_right_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_right_3_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_right_4_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <!--************************-->
+  <!--        WRIST           -->
+  <!--************************-->
+  <!--************************-->
+  <!--        WRIST           -->
+  <!--************************-->
+  <link name="arm_right_5_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00006 0.00326 0.07963"/>
+      <mass value="1.77792"/>
+      <inertia ixx="0.00349500000" ixy="-0.00001300000" ixz="-0.00001000000" iyy="0.00436800000" iyz="0.00009700000" izz="0.00228300000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_5_collision.STL" scale="1 -1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_5_collision.STL" scale="1 -1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_right_5_joint" type="revolute">
+    <parent link="arm_right_4_link"/>
+    <child link="arm_right_5_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="-0.02000 0.00000 -0.26430"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="3" lower="-2.53072741539" upper="2.53072741539" velocity="1.95"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-145.00000 * deg_to_rad + wrist_eps}"
+                          soft_upper_limit="${145.00000 * deg_to_rad - wrist_eps}" /> -->
+  </joint>
+  <link name="arm_right_6_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00002 -0.00197 -0.00059"/>
+      <mass value="0.30931"/>
+      <inertia ixx="0.00010700000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00014100000" iyz="-0.00000000000" izz="0.00015400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_6_collision.STL" scale="1 -1 1"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_6_collision.STL" scale="1 -1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_right_6_joint" type="revolute">
+    <parent link="arm_right_5_link"/>
+    <child link="arm_right_6_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="6.6" lower="-1.3962634016" upper="1.3962634016" velocity="1.76"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-80.00000 * deg_to_rad + eps_radians}"
+                          soft_upper_limit="${80.00000 * deg_to_rad - eps_radians}" /> -->
+  </joint>
+  <link name="arm_right_7_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.007525 0.001378 -0.024630"/>
+      <mass value="0.308441"/>
+      <inertia ixx="0.000309" ixy="0.000002" ixz="-0.000002" iyy="0.000219" iyz="0.000012" izz="0.000176"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_7_collision.STL" scale="1 -1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/arm/arm_7_collision.STL" scale="1 -1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="arm_right_7_joint" type="revolute">
+    <parent link="arm_right_6_link"/>
+    <child link="arm_right_7_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="6.6" lower="-0.698131700798" upper="0.698131700798" velocity="1.76"/>
+    <dynamics damping="1.0" friction="1.0"/>
+    <!--       <safety_controller k_position="20"
+                          k_velocity="20"
+                          soft_lower_limit="${-40.00000 * deg_to_rad + eps_radians}"
+                          soft_upper_limit="${40.00000 * deg_to_rad - eps_radians}" /> -->
+  </joint>
+  <gazebo reference="arm_right_5_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="arm_right_6_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="arm_right_7_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="arm_right_5_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_right_6_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="arm_right_7_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <!-- extensions -->
+  <transmission name="arm_right_5_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_right_5_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_right_5_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="wrist_right_trans">
+    <type>transmission_interface/DifferentialTransmission</type>
+    <actuator name="arm_right_6_motor">
+      <role>actuator1</role>
+      <mechanicalReduction>-1.0</mechanicalReduction>
+    </actuator>
+    <actuator name="arm_right_7_motor">
+      <role>actuator2</role>
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_right_6_joint">
+      <role>joint1</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>-1.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+    <joint name="arm_right_7_joint">
+      <role>joint2</role>
+      <offset>0.0</offset>
+      <mechanicalReduction>1.0</mechanicalReduction>
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <!-- extensions -->
+  <transmission name="arm_right_1_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_right_1_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_right_1_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="arm_right_2_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_right_2_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_right_2_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="arm_right_3_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_right_3_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_right_3_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="arm_right_4_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="arm_right_4_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="arm_right_4_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <!--************************-->
+  <!--        ft sensor       -->
+  <!--************************-->
+  <link name="wrist_right_ft_link">
+    <inertial>
+      <mass value="0.1"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <cylinder length="0.0157" radius="0.0225"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <cylinder length="0.0157" radius="0.0225"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="wrist_right_ft_joint" type="fixed">
+    <parent link="arm_right_7_link"/>
+    <child link="wrist_right_ft_link"/>
+    <origin rpy="0.0 0 -1.57079632679" xyz="0 0 -0.051"/>
+  </joint>
+  <!--***********************-->
+  <!--       FT TOOL         -->
+  <!--***********************-->
+  <link name="wrist_right_ft_tool_link">
+    <inertial>
+      <mass value="0.1"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0.0 0" xyz="0.0 0 0"/>
+      <geometry>
+        <cylinder length="0.00975" radius="0.025"/>
+      </geometry>
+      <material name="FlatBlack"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0.0 0" xyz="0.0 0 0"/>
+      <geometry>
+        <cylinder length="0.00975" radius="0.025"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="wrist_right_tool_joint" type="fixed">
+    <parent link="wrist_right_ft_link"/>
+    <child link="wrist_right_ft_tool_link"/>
+    <origin rpy="0 0 -1.57079632679" xyz="0 0 -0.012725"/>
+  </joint>
+  <!--************************-->
+  <!--        ft sensor       -->
+  <!--************************-->
+  <link name="wrist_left_ft_link">
+    <inertial>
+      <mass value="0.1"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <cylinder length="0.0157" radius="0.0225"/>
+      </geometry>
+      <material name="LightGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <cylinder length="0.0157" radius="0.0225"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="wrist_left_ft_joint" type="fixed">
+    <parent link="arm_left_7_link"/>
+    <child link="wrist_left_ft_link"/>
+    <origin rpy="0.0 0 -4.71238898038" xyz="0 0 -0.051"/>
+  </joint>
+  <!--***********************-->
+  <!--       FT TOOL         -->
+  <!--***********************-->
+  <link name="wrist_left_ft_tool_link">
+    <inertial>
+      <mass value="0.1"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0.0 0" xyz="0.0 0 0"/>
+      <geometry>
+        <cylinder length="0.00975" radius="0.025"/>
+      </geometry>
+      <material name="FlatBlack"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0.0 0" xyz="0.0 0 0"/>
+      <geometry>
+        <cylinder length="0.00975" radius="0.025"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="wrist_left_tool_joint" type="fixed">
+    <parent link="wrist_left_ft_link"/>
+    <child link="wrist_left_ft_tool_link"/>
+    <origin rpy="0 0 4.71238898038" xyz="0 0 -0.012725"/>
+  </joint>
+  <link name="gripper_left_base_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00534 0.00362 -0.02357"/>
+      <mass value="0.61585"/>
+      <inertia ixx="0.00047200000" ixy="-0.00000800000" ixz="0.00003500000" iyy="0.00052100000" iyz="0.00000000000" izz="0.00069000000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/base_link.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/base_link_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_base_link_joint" type="fixed">
+    <parent link="wrist_left_ft_tool_link"/>
+    <child link="gripper_left_base_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.02875"/>
+    <axis xyz="0 0 0"/>
+  </joint>
+  <link name="gripper_left_motor_double_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02270 0.01781 -0.00977"/>
+      <mass value="0.16889"/>
+      <!-- In order for Gazebo not to explode we needed to add these 0.001 values to the diagonal,
+                also the tool pal_dynamics InertiaMassVisualization gave NaN on the computation of the inertia box -->
+      <inertia ixx="0.001159" ixy="-0.00007000000" ixz="0.00003800000" iyy="0.001221" iyz="-0.00005300000" izz="0.001268"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_double.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_joint" type="revolute">
+    <parent link="gripper_left_base_link"/>
+    <child link="gripper_left_motor_double_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.02025 -0.03"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="1.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/>
+    <dynamics damping="1.0" friction="1.0"/>
+  </joint>
+  <link name="gripper_left_inner_double_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00056 0.03358 -0.01741"/>
+      <mass value="0.11922"/>
+      <inertia ixx="0.00009100000" ixy="0.00000100000" ixz="-0.00000100000" iyy="0.00015600000" iyz="-0.00003200000" izz="0.00012600000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_double.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_inner_double_joint" type="fixed">
+    <parent link="gripper_left_base_link"/>
+    <child link="gripper_left_inner_double_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00525 -0.05598"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/>
+    <mimic joint="gripper_left_joint" multiplier="1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_left_fingertip_1_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/>
+      <mass value="0.02630"/>
+      <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_fingertip_1_joint" type="fixed">
+    <parent link="gripper_left_inner_double_link"/>
+    <child link="gripper_left_fingertip_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.03200 0.04589 -0.06553"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_left_fingertip_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/>
+      <mass value="0.02630"/>
+      <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_fingertip_2_joint" type="fixed">
+    <parent link="gripper_left_inner_double_link"/>
+    <child link="gripper_left_fingertip_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="-0.03200 0.04589 -0.06553"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_left_motor_single_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02589 -0.01284 -0.00640"/>
+      <mass value="0.14765"/>
+      <inertia ixx="0.00011500000" ixy="0.00005200000" ixz="0.00002500000" iyy="0.00015300000" iyz="0.00003400000" izz="0.00019000000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_single.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_motor_single_joint" type="fixed">
+    <parent link="gripper_left_base_link"/>
+    <child link="gripper_left_motor_single_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.02025 -0.03000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_left_inner_single_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.03253 -0.01883"/>
+      <mass value="0.05356"/>
+      <inertia ixx="0.00004700000" ixy="-0.00000000000" ixz="-0.00000000000" iyy="0.00003500000" iyz="0.00001700000" izz="0.00002400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_single.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_inner_single_joint" type="fixed">
+    <parent link="gripper_left_base_link"/>
+    <child link="gripper_left_inner_single_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.00525 -0.05598"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_left_fingertip_3_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/>
+      <mass value="0.02630"/>
+      <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_left_fingertip_3_joint" type="fixed">
+    <parent link="gripper_left_inner_single_link"/>
+    <child link="gripper_left_fingertip_3_link"/>
+    <origin rpy="0.0 0.0 3.14159265359" xyz="0.00000 -0.04589 -0.06553"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_left_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <gazebo>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_inner_double_joint">
+      <joint>gripper_left_joint</joint>
+      <mimicJoint>gripper_left_inner_double_joint</mimicJoint>
+      <multiplier>1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_fingertip_1_joint">
+      <joint>gripper_left_joint</joint>
+      <mimicJoint>gripper_left_fingertip_1_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_fingertip_2_joint">
+      <joint>gripper_left_joint</joint>
+      <mimicJoint>gripper_left_fingertip_2_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_inner_single_joint">
+      <joint>gripper_left_joint</joint>
+      <mimicJoint>gripper_left_inner_single_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_motor_single_joint">
+      <joint>gripper_left_joint</joint>
+      <mimicJoint>gripper_left_motor_single_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_left_fingertip_3_joint">
+      <joint>gripper_left_joint</joint>
+      <mimicJoint>gripper_left_fingertip_3_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+  </gazebo>
+  <!--     <plugin filename="libgazebo_underactuated_finger.so" name="gazebo_${name}_underactuated">
+      <actuatedJoint>${name}_joint</actuatedJoint>
+      <virtualJoint>
+        <name>${name}_inner_double_joint</name>
+        <scale_factor>1.0</scale_factor>
+      </virtualJoint> -->
+  <!--       <virtualJoint>
+        <name>${name}_fingertip_1_joint</name>
+        <scale_factor>-1.0</scale_factor>
+      </virtualJoint>
+      <virtualJoint>
+        <name>${name}_fingertip_2_joint</name>
+        <scale_factor>-1.0</scale_factor>
+      </virtualJoint>
+      <virtualJoint>
+        <name>${name}_motor_single_joint</name>
+        <scale_factor>1.0</scale_factor>
+      </virtualJoint>
+      <virtualJoint>
+        <name>${name}_fingertip_3_joint</name>
+        <scale_factor>-1.0</scale_factor>
+      </virtualJoint> -->
+  <!--     </plugin> -->
+  <gazebo reference="gripper_left_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_left_inner_double_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_left_fingertip_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_left_fingertip_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_left_motor_single_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_left_fingertip_3_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_left_base_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="gripper_left_motor_double_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_left_inner_double_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_left_fingertip_1_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="gripper_left_motor_single_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_left_inner_single_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_left_fingertip_2_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="gripper_left_fingertip_3_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <transmission name="gripper_left_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="gripper_left_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="gripper_left_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <!-- virtual mimic joints -->
+  <!--         <xacro:gripper_virtual_transmission name="${name}_inner_double" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_fingertip_1" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_fingertip_2" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_inner_single" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_motor_single" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_fingertip_3" reduction="1.0"/> -->
+  <link name="gripper_right_base_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00534 0.00362 -0.02357"/>
+      <mass value="0.61585"/>
+      <inertia ixx="0.00047200000" ixy="-0.00000800000" ixz="0.00003500000" iyy="0.00052100000" iyz="0.00000000000" izz="0.00069000000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/base_link.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/base_link_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_base_link_joint" type="fixed">
+    <parent link="wrist_right_ft_tool_link"/>
+    <child link="gripper_right_base_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.02875"/>
+    <axis xyz="0 0 0"/>
+  </joint>
+  <link name="gripper_right_motor_double_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02270 0.01781 -0.00977"/>
+      <mass value="0.16889"/>
+      <!-- In order for Gazebo not to explode we needed to add these 0.001 values to the diagonal,
+                also the tool pal_dynamics InertiaMassVisualization gave NaN on the computation of the inertia box -->
+      <inertia ixx="0.001159" ixy="-0.00007000000" ixz="0.00003800000" iyy="0.001221" iyz="-0.00005300000" izz="0.001268"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_double.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_joint" type="revolute">
+    <parent link="gripper_right_base_link"/>
+    <child link="gripper_right_motor_double_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.02025 -0.03"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="1.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/>
+    <dynamics damping="1.0" friction="1.0"/>
+  </joint>
+  <link name="gripper_right_inner_double_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.00056 0.03358 -0.01741"/>
+      <mass value="0.11922"/>
+      <inertia ixx="0.00009100000" ixy="0.00000100000" ixz="-0.00000100000" iyy="0.00015600000" iyz="-0.00003200000" izz="0.00012600000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_double.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_inner_double_joint" type="fixed">
+    <parent link="gripper_right_base_link"/>
+    <child link="gripper_right_inner_double_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00525 -0.05598"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="-1.0471975512" upper="0.0" velocity="1.0"/>
+    <mimic joint="gripper_right_joint" multiplier="1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_right_fingertip_1_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/>
+      <mass value="0.02630"/>
+      <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_fingertip_1_joint" type="fixed">
+    <parent link="gripper_right_inner_double_link"/>
+    <child link="gripper_right_fingertip_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.03200 0.04589 -0.06553"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_right_fingertip_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/>
+      <mass value="0.02630"/>
+      <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_fingertip_2_joint" type="fixed">
+    <parent link="gripper_right_inner_double_link"/>
+    <child link="gripper_right_fingertip_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="-0.03200 0.04589 -0.06553"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_right_motor_single_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02589 -0.01284 -0.00640"/>
+      <mass value="0.14765"/>
+      <inertia ixx="0.00011500000" ixy="0.00005200000" ixz="0.00002500000" iyy="0.00015300000" iyz="0.00003400000" izz="0.00019000000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_single.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_motor_single_joint" type="fixed">
+    <parent link="gripper_right_base_link"/>
+    <child link="gripper_right_motor_single_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.02025 -0.03000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_right_inner_single_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.03253 -0.01883"/>
+      <mass value="0.05356"/>
+      <inertia ixx="0.00004700000" ixy="-0.00000000000" ixz="-0.00000000000" iyy="0.00003500000" iyz="0.00001700000" izz="0.00002400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_single.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="Orange"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_inner_single_joint" type="fixed">
+    <parent link="gripper_right_base_link"/>
+    <child link="gripper_right_inner_single_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.00525 -0.05598"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <link name="gripper_right_fingertip_3_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00460 -0.00254"/>
+      <mass value="0.02630"/>
+      <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" iyy="0.00000900000" iyz="0.00000100000" izz="0.00000200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip.STL" scale="1 1 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="gripper_right_fingertip_3_joint" type="fixed">
+    <parent link="gripper_right_inner_single_link"/>
+    <child link="gripper_right_fingertip_3_link"/>
+    <origin rpy="0.0 0.0 3.14159265359" xyz="0.00000 -0.04589 -0.06553"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100.0" lower="0.0" upper="1.0471975512" velocity="1.0"/>
+    <mimic joint="gripper_right_joint" multiplier="-1.0" offset="0.0"/>
+  </joint>
+  <gazebo>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_inner_double_joint">
+      <joint>gripper_right_joint</joint>
+      <mimicJoint>gripper_right_inner_double_joint</mimicJoint>
+      <multiplier>1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_fingertip_1_joint">
+      <joint>gripper_right_joint</joint>
+      <mimicJoint>gripper_right_fingertip_1_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_fingertip_2_joint">
+      <joint>gripper_right_joint</joint>
+      <mimicJoint>gripper_right_fingertip_2_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_inner_single_joint">
+      <joint>gripper_right_joint</joint>
+      <mimicJoint>gripper_right_inner_single_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_motor_single_joint">
+      <joint>gripper_right_joint</joint>
+      <mimicJoint>gripper_right_motor_single_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+    <plugin filename="libroboticsgroup_gazebo_mimic_joint_plugin.so" name="mimic_gripper_right_fingertip_3_joint">
+      <joint>gripper_right_joint</joint>
+      <mimicJoint>gripper_right_fingertip_3_joint</mimicJoint>
+      <multiplier>-1.0</multiplier>
+      <offset>0.0</offset>
+      <!-- <hasPID/> -->
+    </plugin>
+  </gazebo>
+  <!--     <plugin filename="libgazebo_underactuated_finger.so" name="gazebo_${name}_underactuated">
+      <actuatedJoint>${name}_joint</actuatedJoint>
+      <virtualJoint>
+        <name>${name}_inner_double_joint</name>
+        <scale_factor>1.0</scale_factor>
+      </virtualJoint> -->
+  <!--       <virtualJoint>
+        <name>${name}_fingertip_1_joint</name>
+        <scale_factor>-1.0</scale_factor>
+      </virtualJoint>
+      <virtualJoint>
+        <name>${name}_fingertip_2_joint</name>
+        <scale_factor>-1.0</scale_factor>
+      </virtualJoint>
+      <virtualJoint>
+        <name>${name}_motor_single_joint</name>
+        <scale_factor>1.0</scale_factor>
+      </virtualJoint>
+      <virtualJoint>
+        <name>${name}_fingertip_3_joint</name>
+        <scale_factor>-1.0</scale_factor>
+      </virtualJoint> -->
+  <!--     </plugin> -->
+  <gazebo reference="gripper_right_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_right_inner_double_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_right_fingertip_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_right_fingertip_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_right_motor_single_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_right_fingertip_3_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="gripper_right_base_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="gripper_right_motor_double_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_right_inner_double_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_right_fingertip_1_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="gripper_right_motor_single_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_right_inner_single_link">
+    <material>Gazebo/Orange</material>
+  </gazebo>
+  <gazebo reference="gripper_right_fingertip_2_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="gripper_right_fingertip_3_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <transmission name="gripper_right_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="gripper_right_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="gripper_right_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <!-- virtual mimic joints -->
+  <!--         <xacro:gripper_virtual_transmission name="${name}_inner_double" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_fingertip_1" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_fingertip_2" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_inner_single" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_motor_single" reduction="1.0"/>
+        <xacro:gripper_virtual_transmission name="${name}_fingertip_3" reduction="1.0"/> -->
+  <!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
+  <link name="leg_left_1_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
+      <mass value="1.88569"/>
+      <inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_z_lo_res.stl" scale="1 1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_z_collision.stl" scale="1 1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_left_1_joint" type="revolute">
+    <parent link="base_link"/>
+    <child link="leg_left_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="-0.02 0.085 -0.27105"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="100" lower="-0.349065850399" upper="1.57079632679" velocity="3.87"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
+  <link name="leg_left_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
+      <mass value="2.37607"/>
+      <inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0  0  0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0  0  0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_x_collision.stl" scale="1 1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_left_2_joint" type="revolute">
+    <parent link="leg_left_1_link"/>
+    <child link="leg_left_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
+  <link name="leg_left_3_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 0.06563 -0.17278"/>
+      <mass value="6.82734"/>
+      <inertia ixx="0.12390600000" ixy="-0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="0.016725" izz="0.02781200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_y_lo_res.stl" scale="1 1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_y_collision.stl" scale="1 1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_left_3_joint" type="revolute">
+    <parent link="leg_left_2_link"/>
+    <child link="leg_left_3_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
+  <link name="leg_left_4_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 0.02331 -0.12063"/>
+      <mass value="3.63668"/>
+      <inertia ixx="0.03531500000" ixy="2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="-0.001305" izz="0.01174000000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/knee_lo_res.stl" scale="1 1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/knee_collision.stl" scale="1 1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_left_4_joint" type="revolute">
+    <parent link="leg_left_3_link"/>
+    <child link="leg_left_4_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="300" lower="0" upper="2.618" velocity="7"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
+  <link name="leg_left_5_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 0.04708 0.05271"/>
+      <mass value="1.24433"/>
+      <inertia ixx="0.01148700000" ixy="-0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="0.002633" izz="0.00390800000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 1.0 1"/>
+      </geometry>
+      <material name="Grey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_left_5_joint" type="revolute">
+    <parent link="leg_left_4_link"/>
+    <child link="leg_left_5_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
+  <link name="leg_left_6_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
+      <mass value="1.59457"/>
+      <inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 1.0 1"/>
+      </geometry>
+      <material name="Grey"/>
+    </visual>
+    <collision>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_X_collision.stl" scale="1 1 1"/>
+      </geometry>
+    </collision> 
+  </link>
+  <joint name="leg_left_6_joint" type="revolute">
+    <parent link="leg_left_5_link"/>
+    <child link="leg_left_6_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- from here is copy paste -->
+  <link name="left_sole_link">
+    <inertial>
+      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+      <mass value="0.01"/>
+      <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
+    </inertial>
+  </link>
+  <joint name="leg_left_sole_fix_joint" type="fixed">
+    <parent link="leg_left_6_link"/>
+    <child link="left_sole_link"/>
+    <origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
+    <axis xyz="1 0 0"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <transmission name="leg_left_1_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_left_1_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_left_1_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_left_2_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_left_2_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_left_2_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_left_3_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_left_3_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_left_3_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_left_4_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_left_4_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_left_4_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_left_5_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_left_5_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_left_5_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_left_6_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_left_6_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_left_6_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <gazebo reference="leg_left_1_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_left_2_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_left_3_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_left_4_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_left_5_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <!-- contact model for foot surface -->
+  <gazebo reference="leg_left_6_link">
+    <kp>1000000.0</kp>
+    <kd>100.0</kd>
+    <mu1>1.0</mu1>
+    <mu2>1.0</mu2>
+    <fdir1>1 0 0</fdir1>
+    <maxVel>1.0</maxVel>
+    <minDepth>0.00</minDepth>
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_left_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_left_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_left_3_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_left_4_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_left_5_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_left_6_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="leg_left_1_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_left_2_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_left_3_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_left_4_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_left_5_link">
+    <material>Gazebo/White</material>
+  </gazebo>
+  <gazebo reference="leg_left_6_link">
+    <material>Gazebo/White</material>
+  </gazebo>
+  <!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
+  <link name="leg_right_1_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.02320 -0.00009 0.04949"/>
+      <mass value="1.88569"/>
+      <inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" iyy="0.00599400000" iyz="0.00007800000" izz="0.00322200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_z_lo_res.stl" scale="1 -1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_z_collision.stl" scale="1 -1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_right_1_joint" type="revolute">
+    <parent link="base_link"/>
+    <child link="leg_right_1_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="-0.02 -0.085 -0.27105"/>
+    <axis xyz="0 0 1"/>
+    <limit effort="100" lower="-1.57079632679" upper="0.349065850399" velocity="3.87"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
+  <link name="leg_right_2_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.01583 -0.00021 0.00619"/>
+      <mass value="2.37607"/>
+      <inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" iyy="0.00402400000" iyz="-0.00003100000" izz="0.00416400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0  0  0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_x_lo_res.stl" scale="1 -1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0  0  0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_x_collision.stl" scale="1 -1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_right_2_joint" type="revolute">
+    <parent link="leg_right_1_link"/>
+    <child link="leg_right_2_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="160" lower="-0.5236" upper="0.5236" velocity="5.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
+  <link name="leg_right_3_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.00658 -0.06563 -0.17278"/>
+      <mass value="6.82734"/>
+      <inertia ixx="0.12390600000" ixy="0.000412" ixz="-0.00205900000" iyy="0.10844700000" iyz="-0.016725" izz="0.02781200000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_y_lo_res.stl" scale="1 -1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/hip_y_collision.stl" scale="1 -1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_right_3_joint" type="revolute">
+    <parent link="leg_right_2_link"/>
+    <child link="leg_right_3_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="160" lower="-2.095" upper="0.7" velocity="5.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
+  <link name="leg_right_4_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="0.01520 -0.02331 -0.12063"/>
+      <mass value="3.63668"/>
+      <inertia ixx="0.03531500000" ixy="-2.9e-05" ixz="-0.00016600000" iyy="0.02933600000" iyz="0.001305" izz="0.01174000000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/knee_lo_res.stl" scale="1 -1.0 1"/>
+      </geometry>
+      <material name="DarkGrey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/knee_collision.stl" scale="1 -1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_right_4_joint" type="revolute">
+    <parent link="leg_right_3_link"/>
+    <child link="leg_right_4_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.38000"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="300" lower="0" upper="2.618" velocity="7"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
+  <link name="leg_right_5_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.01106 -0.04708 0.05271"/>
+      <mass value="1.24433"/>
+      <inertia ixx="0.01148700000" ixy="0.000686" ixz="-0.00052600000" iyy="0.00952600000" iyz="-0.002633" izz="0.00390800000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_Y_lo_res.stl" scale="1 -1.0 1"/>
+      </geometry>
+      <material name="Grey"/>
+    </visual>
+    <collision>
+      <origin rpy="0 0 0" xyz="0 0 0.0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_Y_collision.stl" scale="1 -1.0 1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint name="leg_right_5_joint" type="revolute">
+    <parent link="leg_right_4_link"/>
+    <child link="leg_right_5_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 -0.32500"/>
+    <axis xyz="0 1 0"/>
+    <limit effort="160" lower="-1.309" upper="0.768" velocity="5.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
+  <link name="leg_right_6_link">
+    <inertial>
+      <origin rpy="0.00000 0.00000 0.00000" xyz="-0.02087 -0.00019 -0.06059"/>
+      <mass value="1.59457"/>
+      <inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" iyy="0.00657200000" iyz="-0.00001700000" izz="0.00504400000"/>
+    </inertial>
+    <visual>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_X_lo_res.stl" scale="1 -1.0 1"/>
+      </geometry>
+      <material name="Grey"/>
+    </visual>
+    <collision>
+      <origin xyz="0 0 0" rpy="0 0 0" />
+      <geometry>
+        <mesh filename="package://example-robot-data/robots/talos_data/meshes/v2/ankle_X_collision.stl" scale="1 -1 1"/>
+      </geometry>
+    </collision> 
+  </link>
+  <joint name="leg_right_6_joint" type="revolute">
+    <parent link="leg_right_5_link"/>
+    <child link="leg_right_6_link"/>
+    <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00000 0.00000"/>
+    <axis xyz="1 0 0"/>
+    <limit effort="100" lower="-0.5236" upper="0.5236" velocity="4.8"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <!-- from here is copy paste -->
+  <link name="right_sole_link">
+    <inertial>
+      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
+      <mass value="0.01"/>
+      <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
+    </inertial>
+  </link>
+  <joint name="leg_right_sole_fix_joint" type="fixed">
+    <parent link="leg_right_6_link"/>
+    <child link="right_sole_link"/>
+    <origin rpy="0 0 0" xyz="0.00 0.00 -0.107"/>
+    <axis xyz="1 0 0"/>
+    <dynamics damping="0.0" friction="0.0"/>
+  </joint>
+  <transmission name="leg_right_1_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_right_1_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_right_1_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_right_2_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_right_2_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_right_2_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_right_3_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_right_3_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_right_3_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_right_4_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_right_4_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_right_4_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_right_5_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_right_5_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_right_5_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <transmission name="leg_right_6_trans">
+    <type>transmission_interface/SimpleTransmission</type>
+    <actuator name="leg_right_6_motor">
+      <mechanicalReduction>1.0</mechanicalReduction>
+    </actuator>
+    <joint name="leg_right_6_joint">
+      <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
+      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
+    </joint>
+  </transmission>
+  <gazebo reference="leg_right_1_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_right_2_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_right_3_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_right_4_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <gazebo reference="leg_right_5_link">
+    <mu1>0.9</mu1>
+    <mu2>0.9</mu2>
+  </gazebo>
+  <!-- contact model for foot surface -->
+  <gazebo reference="leg_right_6_link">
+    <kp>1000000.0</kp>
+    <kd>100.0</kd>
+    <mu1>1.0</mu1>
+    <mu2>1.0</mu2>
+    <fdir1>1 0 0</fdir1>
+    <maxVel>1.0</maxVel>
+    <minDepth>0.00</minDepth>
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_right_1_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_right_2_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_right_3_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_right_4_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_right_5_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+  </gazebo>
+  <gazebo reference="leg_right_6_joint">
+    <implicitSpringDamper>1</implicitSpringDamper>
+    <provideFeedback>1</provideFeedback>
+  </gazebo>
+  <gazebo reference="leg_right_1_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_right_2_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_right_3_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_right_4_link">
+    <material>Gazebo/FlatBlack</material>
+  </gazebo>
+  <gazebo reference="leg_right_5_link">
+    <material>Gazebo/White</material>
+  </gazebo>
+  <gazebo reference="leg_right_6_link">
+    <material>Gazebo/White</material>
+  </gazebo>
+  <!-- Generic simulatalos_gazebo plugins -->
+  <gazebo>
+    <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
+      <ns/>
+      <robotSimType>pal_hardware_gazebo/PalHardwareGazebo</robotSimType>
+      <robotNamespace/>
+      <controlPeriod>0.001</controlPeriod>
+    </plugin>
+  </gazebo>
+  <gazebo>
+    <plugin filename="libgazebo_world_odometry.so" name="gazebo_ros_odometry">
+      <frameName>base_link</frameName>
+      <topicName>floating_base_pose_simulated</topicName>
+    </plugin>
+  </gazebo>
+  <gazebo>
+    <plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
+      <bodyName>base_link</bodyName>
+      <topicName>wrench</topicName>
+    </plugin>
+  </gazebo>
+  <gazebo reference="imu_link">
+    <!-- this is expected to be reparented to pelvis with appropriate offset
+         when imu_link is reduced by fixed joint reduction -->
+    <!-- todo: this is working with gazebo 1.4, need to write a unit test -->
+    <sensor name="imu_sensor" type="imu">
+      <always_on>1</always_on>
+      <update_rate>1000.0</update_rate>
+      <imu>
+        <noise>
+          <type>gaussian</type>
+          <!-- Noise parameters from Boston Dynamics
+               (http://gazebosim.org/wiki/Sensor_noise):
+                 rates (rad/s): mean=0, stddev=2e-4
+                 accels (m/s/s): mean=0, stddev=1.7e-2
+                 rate bias (rad/s): 5e-6 - 1e-5
+                 accel bias (m/s/s): 1e-1
+               Experimentally, simulation provide rates with noise of
+               about 1e-3 rad/s and accels with noise of about 1e-1 m/s/s.
+               So we don't expect to see the noise unless number of inner iterations
+               are increased.
+
+               We will add bias.  In this model, bias is sampled once for rates
+               and once for accels at startup; the sign (negative or positive)
+               of each bias is then switched with equal probability.  Thereafter,
+               the biases are fixed additive offsets.  We choose
+               bias means and stddevs to produce biases close to the provided
+               data. -->
+          <!--
+          <rate>
+            <mean>0.0</mean>
+            <stddev>2e-4</stddev>
+            <bias_mean>0.0000075</bias_mean>
+            <bias_stddev>0.0000008</bias_stddev>
+          </rate>
+          <accel>
+            <mean>0.0</mean>
+            <stddev>1.7e-2</stddev>
+            <bias_mean>0.1</bias_mean>
+            <bias_stddev>0.001</bias_stddev>
+          </accel>
+          -->
+          <rate>
+            <mean>0.0</mean>
+            <stddev>0.0</stddev>
+            <bias_mean>0.000000</bias_mean>
+            <bias_stddev>0.0000008</bias_stddev>
+          </rate>
+          <accel>
+            <mean>0.0</mean>
+            <stddev>0.0</stddev>
+            <bias_mean>0.0</bias_mean>
+            <bias_stddev>0.000</bias_stddev>
+          </accel>
+        </noise>
+      </imu>
+    </sensor>
+  </gazebo>
+  <!-- define global properties -->
+  <!-- <xacro:property name="M_PI" value="3.1415926535897931" /> -->
+  <!-- Materials for visualization -->
+  <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.7 0.7 0.7 1.0"/>
+  </material>
+  <material name="LightGrey">
+    <color rgba="0.9 0.9 0.9 1.0"/>
+  </material>
+  <material name="DarkGrey">
+    <color rgba="0.2 0.2 0.2 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>
+  <material name="Orange">
+    <color rgba="1.0 0.5 0.0 1.0"/>
+  </material>
+</robot>
+
diff --git a/robots/tiago_description/robots/tiago.urdf b/robots/tiago_description/robots/tiago.urdf
index 9a8ea780c1214963b08e4c34d3bba9068f8764ff..f05f48c9e80132284a4b5d200bb9a94439699fd4 100644
--- a/robots/tiago_description/robots/tiago.urdf
+++ b/robots/tiago_description/robots/tiago.urdf
@@ -132,7 +132,13 @@
     <material>Gazebo/White</material>
   </gazebo>
   <!-- Base footprint -->
-  <link name="base_footprint"/>
+  <link name="base_footprint">
+    <inertial>
+      <mass value="0.0"/>
+      <origin xyz="0.0 0.0 0.0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
   <joint name="base_footprint_joint" type="fixed">
     <origin rpy="0 0 0" xyz="0 0 0.0985"/>
     <child link="base_link"/>
@@ -2959,7 +2965,13 @@
       <mechanicalReduction>0.0739176962651</mechanicalReduction>
     </actuator>
   </transmission>
-  <link name="hand_grasping_frame"/>
+  <link name="hand_grasping_frame">
+    <inertial>
+      <mass value="0.0"/>
+      <origin xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0" izz="0.0"/>
+    </inertial>
+  </link>
   <joint name="hand_grasping_fixed_joint" type="fixed">
     <parent link="hand_palm_link"/>
     <child link="hand_grasping_frame"/>
diff --git a/robots/tiago_description/robots/tiago_no_hand.urdf b/robots/tiago_description/robots/tiago_no_hand.urdf
index d088c5d3e7a3c9534afc3320f3b4b945d866e5ee..94f9ad0842208d45db4c7225f76995bccc58d9e2 100644
--- a/robots/tiago_description/robots/tiago_no_hand.urdf
+++ b/robots/tiago_description/robots/tiago_no_hand.urdf
@@ -132,7 +132,14 @@
     <material>Gazebo/White</material>
   </gazebo>
   <!-- Base footprint -->
-  <link name="base_footprint"/>
+  <link name="base_footprint">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+    
   <joint name="base_footprint_joint" type="fixed">
     <origin rpy="0 0 0" xyz="0 0 0.0985"/>
     <child link="base_link"/>
diff --git a/robots/ur_description/urdf/ur10_robot.urdf b/robots/ur_description/urdf/ur10_robot.urdf
index a174c7d0e0e167c7abc4f32e064671e8ea0dabd2..5bc3ff2ac32c1e806cf1112206bd514ce50e0fc6 100644
--- a/robots/ur_description/urdf/ur10_robot.urdf
+++ b/robots/ur_description/urdf/ur10_robot.urdf
@@ -229,7 +229,13 @@
       </geometry>
       <origin rpy="0 0 0" xyz="-0.01 0 0"/>
     </collision>
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
   </link>
+  
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
     <joint name="shoulder_pan_joint">
@@ -306,7 +312,14 @@
     <selfCollide>true</selfCollide>
   </gazebo>
   <!-- ROS base_link to UR 'Base' Coordinates transform -->
-  <link name="base"/>
+  <link name="base">        
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+
   <joint name="base_link-base_fixed_joint" type="fixed">
     <!-- NOTE: this rotation is only needed as long as base_link itself is
                  not corrected wrt the real robot (ie: rotated over 180
@@ -317,7 +330,14 @@
     <child link="base"/>
   </joint>
   <!-- Frame coincident with all-zeros TCP on UR controller -->
-  <link name="tool0"/>
+  <link name="tool0">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+  
   <joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
     <origin rpy="-1.57079632679 0 0" xyz="0 0.0922 0"/>
     <parent link="wrist_3_link"/>
diff --git a/robots/ur_description/urdf/ur3_joint_limited_robot.urdf b/robots/ur_description/urdf/ur3_joint_limited_robot.urdf
index 6c13ca1e669aa8195ea2afcac344cbae832abdac..55ad8b1a1f98ad5db8bf403333f7aa14518a8915 100644
--- a/robots/ur_description/urdf/ur3_joint_limited_robot.urdf
+++ b/robots/ur_description/urdf/ur3_joint_limited_robot.urdf
@@ -228,6 +228,11 @@
       </geometry>
       <origin rpy="0 0 0" xyz="-0.01 0 0"/>
     </collision>
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>            
   </link>
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
@@ -305,7 +310,13 @@
     <selfCollide>true</selfCollide>
   </gazebo>
   <!-- ROS base_link to UR 'Base' Coordinates transform -->
-  <link name="base"/>
+  <link name="base">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
   <joint name="base_link-base_fixed_joint" type="fixed">
     <!-- NOTE: this rotation is only needed as long as base_link itself is
                  not corrected wrt the real robot (ie: rotated over 180
@@ -316,7 +327,14 @@
     <child link="base"/>
   </joint>
   <!-- Frame coincident with all-zeros TCP on UR controller -->
-  <link name="tool0"/>
+  <link name="tool0">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+
   <joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
     <origin rpy="-1.57079632679 0 0" xyz="0 0.0819 0"/>
     <parent link="wrist_3_link"/>
diff --git a/robots/ur_description/urdf/ur3_robot.urdf b/robots/ur_description/urdf/ur3_robot.urdf
index 54b18af20dd97024dcea1cf85cb80a855124c475..d4aac18844b2d36bfb63af0b66cf57caf314acff 100644
--- a/robots/ur_description/urdf/ur3_robot.urdf
+++ b/robots/ur_description/urdf/ur3_robot.urdf
@@ -228,6 +228,11 @@
       </geometry>
       <origin rpy="0 0 0" xyz="-0.01 0 0"/>
     </collision>
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
   </link>
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
@@ -305,7 +310,14 @@
     <selfCollide>true</selfCollide>
   </gazebo>
   <!-- ROS base_link to UR 'Base' Coordinates transform -->
-  <link name="base"/>
+  <link name="base">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+  
   <joint name="base_link-base_fixed_joint" type="fixed">
     <!-- NOTE: this rotation is only needed as long as base_link itself is
                  not corrected wrt the real robot (ie: rotated over 180
@@ -316,7 +328,14 @@
     <child link="base"/>
   </joint>
   <!-- Frame coincident with all-zeros TCP on UR controller -->
-  <link name="tool0"/>
+  <link name="tool0">        
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
+
   <joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
     <origin rpy="-1.57079632679 0 0" xyz="0 0.0819 0"/>
     <parent link="wrist_3_link"/>
diff --git a/robots/ur_description/urdf/ur5_gripper.urdf b/robots/ur_description/urdf/ur5_gripper.urdf
index eaf5b05975bf0bc217e5338d77cf9b846fd726e4..45f2901f64ca0bb88e4e8c4d09ec4d1431a6ff9f 100644
--- a/robots/ur_description/urdf/ur5_gripper.urdf
+++ b/robots/ur_description/urdf/ur5_gripper.urdf
@@ -17,7 +17,7 @@
       <timeout>5</timeout>
       <powerStateTopic>power_state</powerStateTopic>
       <powerStateRate>10.0</powerStateRate>
-      <fullChargeCapacity>87.78</fullChargeCapacity>     
+      <fullChargeCapacity>87.78</fullChargeCapacity>
       <dischargeRate>-474</dischargeRate>
       <chargeRate>525</chargeRate>
       <dischargeVoltage>15.52</dischargeVoltage>
@@ -256,6 +256,11 @@
     <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0823 0.0"/>
   </joint>
   <link name="ee_link">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
     <collision>
       <geometry>
         <box size="0.01 0.01 0.01"/>
@@ -319,7 +324,13 @@
   </transmission>
   <!-- nothing to do here at the moment -->
   <!-- ROS base_link to UR 'Base' Coordinates transform -->
-  <link name="base"/>
+  <link name="base">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
+  </link>
   <joint name="base_link-base_fixed_joint" type="fixed">
     <!-- NOTE: this rotation is only needed as long as base_link itself is
                  not corrected wrt the real robot (ie: rotated over 180
@@ -331,6 +342,11 @@
   </joint>
   <!-- Frame coincident with all-zeros TCP on UR controller -->
   <link name="tool0">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
     <visual>
       <geometry>
 	<box size="0.005 0.02 0.05" />
diff --git a/robots/ur_description/urdf/ur5_joint_limited_robot.urdf b/robots/ur_description/urdf/ur5_joint_limited_robot.urdf
index 9d4cbe54bbe145e1c22acfa66e22597189fe6fd7..266efddc82a3fde9434879d051c29f98a576af61 100644
--- a/robots/ur_description/urdf/ur5_joint_limited_robot.urdf
+++ b/robots/ur_description/urdf/ur5_joint_limited_robot.urdf
@@ -238,6 +238,11 @@
       </geometry>
       <origin rpy="0 0 0" xyz="-0.01 0 0"/>
     </collision>
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>    
   </link>
   <transmission name="shoulder_pan_trans">
     <type>transmission_interface/SimpleTransmission</type>
@@ -315,7 +320,13 @@
     <selfCollide>true</selfCollide>
   </gazebo>
   <!-- ROS base_link to UR 'Base' Coordinates transform -->
-  <link name="base"/>
+  <link name="base">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
   <joint name="base_link-base_fixed_joint" type="fixed">
     <!-- NOTE: this rotation is only needed as long as base_link itself is
                  not corrected wrt the real robot (ie: rotated over 180
@@ -326,7 +337,13 @@
     <child link="base"/>
   </joint>
   <!-- Frame coincident with all-zeros TCP on UR controller -->
-  <link name="tool0"/>
+  <link name="tool0">
+    <inertial>
+      <mass value="0.0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>        
+  </link>
   <joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
     <origin rpy="-1.57079632679 0 0" xyz="0 0.0823 0"/>
     <parent link="wrist_3_link"/>
diff --git a/robots/ur_description/urdf/ur5_robot.urdf b/robots/ur_description/urdf/ur5_robot.urdf
index cce6b6aaa0a4b036607ab991ac9614a9f273abb9..49d6cc5269e50e52b78ebc8f784826ef1f93dde7 100644
--- a/robots/ur_description/urdf/ur5_robot.urdf
+++ b/robots/ur_description/urdf/ur5_robot.urdf
@@ -16,7 +16,7 @@
       <timeout>5</timeout>
       <powerStateTopic>power_state</powerStateTopic>
       <powerStateRate>10.0</powerStateRate>
-      <fullChargeCapacity>87.78</fullChargeCapacity>     
+      <fullChargeCapacity>87.78</fullChargeCapacity>
       <dischargeRate>-474</dischargeRate>
       <chargeRate>525</chargeRate>
       <dischargeVoltage>15.52</dischargeVoltage>
@@ -232,6 +232,11 @@
     <origin rpy="0.0 0.0 1.57079632679" xyz="0.0 0.0823 0.0"/>
   </joint>
   <link name="ee_link">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
     <collision>
       <geometry>
         <box size="0.01 0.01 0.01"/>
@@ -315,7 +320,13 @@
     <selfCollide>true</selfCollide>
   </gazebo>
   <!-- ROS base_link to UR 'Base' Coordinates transform -->
-  <link name="base"/>
+  <link name="base">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
+  </link>
   <joint name="base_link-base_fixed_joint" type="fixed">
     <!-- NOTE: this rotation is only needed as long as base_link itself is
                  not corrected wrt the real robot (ie: rotated over 180
@@ -326,7 +337,13 @@
     <child link="base"/>
   </joint>
   <!-- Frame coincident with all-zeros TCP on UR controller -->
-  <link name="tool0"/>
+  <link name="tool0">
+    <inertial>
+      <mass value="0"/>
+      <origin rpy="0 0 0" xyz="0 0 0"/>
+      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
+    </inertial>
+  </link>
   <joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
     <origin rpy="-1.57079632679 0 0" xyz="0 0.0823 0"/>
     <parent link="wrist_3_link"/>
diff --git a/unittest/test_load.py b/unittest/test_load.py
index 9b5d7420cd5d5d07e90feb95fb21c33fc20f62d3..604c3ea5b6e5768c07859c5fef16b482efbfc18f 100755
--- a/unittest/test_load.py
+++ b/unittest/test_load.py
@@ -2,16 +2,34 @@
 
 import unittest
 
-from example_robot_data import load
+try:
+    import pybullet
+except ImportError:
+    pybullet = False
+
+from example_robot_data import load_full
 
 
 class RobotTestCase(unittest.TestCase):
-    def check(self, name, expected_nq, expected_nv):
+    def check(self, name, expected_nq, expected_nv, one_kg_bodies=[]):
         """Helper function for the real tests"""
-        robot = load(name, display=False)
+        robot, _, urdf, _ = load_full(name, display=False)
         self.assertEqual(robot.model.nq, expected_nq)
         self.assertEqual(robot.model.nv, expected_nv)
         self.assertTrue(hasattr(robot, "q0"))
+        if pybullet:
+            self.check_pybullet(urdf, one_kg_bodies)
+
+    def check_pybullet(self, urdf, one_kg_bodies):
+        client_id = pybullet.connect(pybullet.DIRECT)
+        robot_id = pybullet.loadURDF(urdf, physicsClientId=client_id)
+        for joint_id in range(pybullet.getNumJoints(robot_id, client_id)):
+            dynamics = pybullet.getDynamicsInfo(robot_id, joint_id, client_id)
+            if dynamics[0] == 1:
+                joint = pybullet.getJointInfo(robot_id, joint_id, client_id)
+                # with self.subTest():  # uncomment on python >= 3.4 to get full list of wrong bodies at once
+                self.assertIn(joint[12].decode(), one_kg_bodies)
+        pybullet.disconnect(client_id)
 
     def test_anymal(self):
         self.check('anymal', 19, 18)