diff --git a/robots/kinova_description/robots/kinova.urdf b/robots/kinova_description/robots/kinova.urdf
index 2150d315f61352e4256c064081229f20e973e621..dd415c7854afa03bc394e129dc5af138387d502c 100644
--- a/robots/kinova_description/robots/kinova.urdf
+++ b/robots/kinova_description/robots/kinova.urdf
@@ -33,10 +33,6 @@
     <material name="white">
         <color rgba="1.0 1.0 1.0 1.0"/>
     </material>
-    <!-- Material for the visual primitives -->
-    <material name="anymal_material">
-        <color rgba="0.7 0.7 0.7 1.0"/>
-    </material>
     <!-- Xacro:Properties -->
     <!-- [m] -->
     <!-- Base link -->
@@ -48,44 +44,6 @@
       </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"/>
-            </geometry>
-        </visual>
-    </link>
-    <joint name="base_to_jaco_support" type="fixed">
-        <parent link="base"/>
-        <child link="jaco_front_hatch_support_v2"/>
-        <origin rpy="0 0 0" xyz="0 0 0"/>
-    </joint>
-
-    <link name="jaco_mounting_block">
-      <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"/>
-        <child link="jaco_mounting_block"/>
-        <origin rpy="0 0 0" xyz="0.045 0.00 -0.007626"/>
-    </joint>
-
     <link name="j2s6s200_link_base">
         <visual>
             <geometry>
@@ -107,7 +65,7 @@
         </inertial>
     </link>
     <joint name="jaco_mounting_block_to_j2s6s200_link_base" type="fixed">
-        <parent link="jaco_mounting_block"/>
+        <parent link="base"/>
         <child link="j2s6s200_link_base"/>
         <axis xyz="0 0 0"/>
         <limit effort="0" lower="0" upper="0" velocity="0"/>