From 2d376efb951888d6a41f0c146feb58aace27af7b Mon Sep 17 00:00:00 2001
From: Olivier Stasse <ostasse@laas.fr>
Date: Wed, 3 Mar 2021 22:09:20 +0100
Subject: [PATCH] Fix tiago robot

---
 robots/tiago_description/robots/tiago.urdf       | 16 ++++++++++++++--
 .../tiago_description/robots/tiago_no_hand.urdf  |  9 ++++++++-
 2 files changed, 22 insertions(+), 3 deletions(-)

diff --git a/robots/tiago_description/robots/tiago.urdf b/robots/tiago_description/robots/tiago.urdf
index 9a8ea78..f05f48c 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 d088c5d..94f9ad0 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"/>
-- 
GitLab