diff --git a/urdf/talos_reduced.urdf b/urdf/talos_reduced.urdf
index 56bbdfe1b0d9ac9d7a9568b7e67925acd345918e..3f912160d996a4c293957283eeb1abdc25a7649f 100644
--- a/urdf/talos_reduced.urdf
+++ b/urdf/talos_reduced.urdf
@@ -2184,21 +2184,20 @@
       </geometry>
       <material name="Grey"/>
     </visual>
+    <collision>
+    <origin xyz="0 0 0" rpy="0 0 0" />
+    <geometry>
+      <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 1 1"/>
+    </geometry>
+    </collision> 
     <!--
-      <collision>
-        <origin xyz="0 0 0" rpy="0 0 0" />
-        <geometry>
-          <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
-        </geometry>
-      </collision> 
-      
-      -->
     <collision>
       <origin rpy="0 0 0" xyz="0 0 -0.1"/>
       <geometry>
         <box size="0.21 0.13 0.02"/>
       </geometry>
     </collision>
+    -->
   </link>
   <joint name="leg_left_6_joint" type="revolute">
     <parent link="leg_left_5_link"/>
@@ -2510,21 +2509,20 @@
       </geometry>
       <material name="Grey"/>
     </visual>
+    <collision>
+    <origin xyz="0 0 0" rpy="0 0 0" />
+    <geometry>
+      <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 -1 1"/>
+    </geometry>
+    </collision> 
     <!--
-      <collision>
-        <origin xyz="0 0 0" rpy="0 0 0" />
-        <geometry>
-          <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
-        </geometry>
-      </collision> 
-      
-      -->
     <collision>
       <origin rpy="0 0 0" xyz="0 0 -0.1"/>
       <geometry>
         <box size="0.21 0.13 0.02"/>
       </geometry>
     </collision>
+    -->
   </link>
   <joint name="leg_right_6_joint" type="revolute">
     <parent link="leg_right_5_link"/>