diff --git a/config/arm.xacro b/config/arm.xacro
index ea345aa0b57accf020c00b01abe982ab44151f65..fef366a6b565e1dee0b43accd4e3d6b6734b3e1a 100644
--- a/config/arm.xacro
+++ b/config/arm.xacro
@@ -52,13 +52,11 @@
     <xacro:macro name="configure_collisions" params="link enabled:=${[]}">
         <!-- Disable collision checking between normal links, as these are handled by "sc" links -->
         <xacro:property name="link_fmt" value="$(arg arm_id)_link{}" />
-        <xacro:disable_collisions_for link="${link_fmt.format(link)}" others="${[link_fmt.format(i) for i in python.range(9)]}" />
+        <xacro:disable_collisions_for link="${link_fmt.format(link)}" others="${[link_fmt.format(i) for i in python.range(8)]}" />
 
         <!-- Disable all collision checking for ${link}_sc -->
         <xacro:property name="link_fmt" value="$(arg arm_id)_link{}_sc" />
-        <xacro:if value="${link != 8}">
-            <disable_default_collisions link="${link_fmt.format(link)}" />
-        </xacro:if>
+        <disable_default_collisions link="${link_fmt.format(link)}" />
         <!-- Re-enable collisions checking for selected links -->
         <xacro:enable_collisions_for link="${link_fmt.format(link)}" others="${[link_fmt.format(i) for i in enabled]}" />
     </xacro:macro>
@@ -72,5 +70,4 @@
     <xacro:configure_collisions link="5" />
     <xacro:configure_collisions link="6" />
     <xacro:configure_collisions link="7" />
-    <xacro:configure_collisions link="8" />
 </robot>
diff --git a/config/hand.xacro b/config/hand.xacro
index 8c78a1448ada4ecb33f63dcb04a985190b334a86..47a06b658fcf7e4d21aa8139ee9b56600f6010b7 100644
--- a/config/hand.xacro
+++ b/config/hand.xacro
@@ -31,9 +31,9 @@
         <xacro:enable_collisions_for link="$(arg arm_id)_hand_sc" others="${[link_fmt.format(i) for i in [0,1,2,3]]}" />
         <!-- Disable collision of hand link with all arm links. These are handled by the *_sc links -->
         <xacro:property name="link_fmt" value="$(arg arm_id)_link{}" />
-        <xacro:disable_collisions_for link="$(arg arm_id)_hand" others="${[link_fmt.format(i) for i in python.range(9)]}" />
+        <xacro:disable_collisions_for link="$(arg arm_id)_hand" others="${[link_fmt.format(i) for i in python.range(8)]}" />
         <!-- Disable collision of fingers with all arm links -->
-        <xacro:property name="others" value="${[link_fmt.format(i) for i in python.range(9)] + [xacro.arg('arm_id') + '_hand']}" />
+        <xacro:property name="others" value="${[link_fmt.format(i) for i in python.range(8)] + [xacro.arg('arm_id') + '_hand']}" />
         <xacro:disable_collisions_for link="$(arg arm_id)_leftfinger" others="${list(others)}" />
         <xacro:disable_collisions_for link="$(arg arm_id)_rightfinger" others="${list(others)}" />
         <disable_collisions link1="$(arg arm_id)_leftfinger" link2="$(arg arm_id)_rightfinger" reason="Never" />